Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore: sync upstream #143

Merged
merged 28 commits into from
Oct 11, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
1881f97
refactor(route_handler): clang tidy and reserving vector (#1992)
zulfaqar-azmi-t4 Oct 3, 2022
c7698fc
fix(freespace_planner): can't stop before blocking obstacle in parkin…
alanmengg Oct 3, 2022
1c227dc
fix(behavior_path_planner): pull out on lane boundary (#2004)
kosuke55 Oct 4, 2022
c953392
feat(object_merger): add distance_threshold_list (#1902)
Shin-kyoto Oct 4, 2022
80082de
feat(rtc_manager_panel): add rtc all approval (#2009)
taikitanaka3 Oct 4, 2022
ee4f381
fix(avoidance): fix avoidance path chattering (#2012)
satoshi-ota Oct 4, 2022
a6cf5fc
feat(motion_utils): add new resmaple path (#2015)
takayuki5168 Oct 5, 2022
a6b4a86
feat(map_loader): make some functions static (#2014)
takayuki5168 Oct 5, 2022
b5d4e05
refactor(motion_utils): resample (#2020)
takayuki5168 Oct 5, 2022
ce93396
refactor(ndt_scan_matcher): modularize get_transform function (#1984)
kminoda Oct 5, 2022
28a3ccc
fix(behavior_path_planner): not run pull out if out of lane (#2008)
kosuke55 Oct 5, 2022
c2d5b4f
fix: modified to reflect the argument "initial_selector_mode" in cont…
s-azumi Oct 6, 2022
5695431
fix(ground segmentation): add elevation grid ground filter (#1899)
badai-nguyen Oct 6, 2022
5549db4
refactor(perception_utils): refactor perception_utils (#1954)
scepter914 Oct 6, 2022
5af5126
feat(rtc_manager_rviz_plugin): add_indivisual_exe (#2021)
taikitanaka3 Oct 6, 2022
7b63dec
feat(behavior_path_planner): add turn signal document (#2023)
purewater0901 Oct 6, 2022
84a66fe
feat(rtc_reaplyer): add rtc_replayer (#1993)
taikitanaka3 Oct 6, 2022
a07358a
feat(autoware_ad_api_specs): define operation mode interface (#1570)
isamu-takagi Oct 6, 2022
b8a19b5
fix(detected_object_validation): apply transformation to shape.footpr…
Shin-kyoto Oct 6, 2022
d707d2b
feat(obstacle_cruise_planner): add goal safe distance (#2031)
purewater0901 Oct 6, 2022
aa90138
refactor(probabilistic_occupancy_grid): transfer probabilistic_occupa…
YoshiRi Oct 7, 2022
152d293
chore: sync files (#2032)
awf-autoware-bot[bot] Oct 7, 2022
ca09e64
feat(tier4_autoware_utils): add polygon util function (#2029)
scepter914 Oct 7, 2022
365c725
feat(run_out): avoid chattering of state transition (#1975)
TomohitoAndo Oct 7, 2022
5162d75
feat(obstacle_cruise_planner): add an explanation (#2034)
purewater0901 Oct 7, 2022
3a7e174
fix(component_interface_specs): add missing dep (#2035)
maxime-clem Oct 7, 2022
b48b4f5
refactor(perception_util): refactor moving unnamed namespace from inc…
scepter914 Oct 8, 2022
88e9324
feat(tier4_screen_capture_rviz_plugin): add prefix to video name (#2038)
taikitanaka3 Oct 10, 2022
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/build-and-test-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ jobs:

- name: Get modified files
id: get-modified-files
uses: tj-actions/changed-files@v31
uses: tj-actions/changed-files@v32
with:
files: |
**/*.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_AD_API_SPECS__OPERATION_MODE_HPP_
#define AUTOWARE_AD_API_SPECS__OPERATION_MODE_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <autoware_adapi_v1_msgs/srv/change_operation_mode.hpp>

namespace autoware_ad_api::operation_mode
{

struct ChangeToStop
{
using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
static constexpr char name[] = "/api/operation_mode/change_to_stop";
};

struct ChangeToAutonomous
{
using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
static constexpr char name[] = "/api/operation_mode/change_to_autonomous";
};

struct ChangeToLocal
{
using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
static constexpr char name[] = "/api/operation_mode/change_to_local";
};

struct ChangeToRemote
{
using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
static constexpr char name[] = "/api/operation_mode/change_to_remote";
};

struct EnableAutowareControl
{
using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
static constexpr char name[] = "/api/operation_mode/enable_autoware_control";
};

struct DisableAutowareControl
{
using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
static constexpr char name[] = "/api/operation_mode/disable_autoware_control";
};

struct OperationModeState
{
using Message = autoware_adapi_v1_msgs::msg::OperationModeState;
static constexpr char name[] = "/api/operation_mode/state";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace autoware_ad_api::operation_mode

#endif // AUTOWARE_AD_API_SPECS__OPERATION_MODE_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
#define COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <tier4_system_msgs/srv/change_autoware_control.hpp>
#include <tier4_system_msgs/srv/change_operation_mode.hpp>

namespace system_interface
{

struct ChangeAutowareControl
{
using Service = tier4_system_msgs::srv::ChangeAutowareControl;
static constexpr char name[] = "/system/operation_mode/change_autoware_control";
};

struct ChangeOperationMode
{
using Service = tier4_system_msgs::srv::ChangeOperationMode;
static constexpr char name[] = "/system/operation_mode/change_operation_mode";
};

struct OperationModeState
{
using Message = autoware_adapi_v1_msgs::msg::OperationModeState;
static constexpr char name[] = "/system/operation_mode/state";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace system_interface

#endif // COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
2 changes: 2 additions & 0 deletions common/component_interface_specs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_adapi_v1_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
127 changes: 74 additions & 53 deletions common/motion_utils/include/motion_utils/resample/resample.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,39 +39,39 @@ namespace motion_utils
{
/**
* @brief A resampling function for a path(poses). Note that in a default setting, position xy are
* resampled by spline interpolation, position z are resampled by linear interpolation, and
* orientation of the resampled path are calculated by a forward difference method
* based on the interpolated position x and y.
* resampled by spline interpolation, position z are resampled by linear interpolation, and
* orientation of the resampled path are calculated by a forward difference method
* based on the interpolated position x and y.
* @param input_path input path(poses) to resample
* @param resampled_arclength arclength that contains length of each resampling points from initial
* point
* point
* @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and
* y. Otherwise, it uses spline interpolation
* y. Otherwise, it uses spline interpolation
* @param use_lerp_for_z If true, it uses linear interpolation to resample position z.
* Otherwise, it uses spline interpolation
* Otherwise, it uses spline interpolation
* @return resampled path(poses)
*/
std::vector<geometry_msgs::msg::Pose> resamplePath(
std::vector<geometry_msgs::msg::Pose> resamplePoseVector(
const std::vector<geometry_msgs::msg::Pose> & points,
const std::vector<double> & resampled_arclength, const bool use_lerp_for_xy = false,
const bool use_lerp_for_z = true);

/**
* @brief A resampling function for a path with lane id. Note that in a default setting, position xy
* are resampled by spline interpolation, position z are resampled by linear interpolation,
* longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is resampled
* by linear interpolation. Orientation of the resampled path are calculated by a forward difference
* method based on the interpolated position x and y. Moreover, lane_ids and is_final are also
* interpolated by zero order hold
* are resampled by spline interpolation, position z are resampled by linear interpolation,
* longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is
* resampled by linear interpolation. Orientation of the resampled path are calculated by a
* forward difference method based on the interpolated position x and y. Moreover, lane_ids
* and is_final are also interpolated by zero order hold
* @param input_path input path to resample
* @param resampled_arclength arclength that contains length of each resampling points from initial
* point
* point
* @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and
* y. Otherwise, it uses spline interpolation
* y. Otherwise, it uses spline interpolation
* @param use_lerp_for_z If true, it uses linear interpolation to resample position z.
* Otherwise, it uses spline interpolation
* Otherwise, it uses spline interpolation
* @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
* @return resampled path
*/
autoware_auto_planning_msgs::msg::PathWithLaneId resamplePath(
Expand All @@ -81,20 +81,19 @@ autoware_auto_planning_msgs::msg::PathWithLaneId resamplePath(

/**
* @brief A resampling function for a path with lane id. Note that in a default setting, position xy
* are resampled by spline interpolation, position z are resampled by linear interpolation,
* longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is resampled
* by linear interpolation. Orientation of the resampled path are calculated by a forward difference
* method based on the interpolated position x and y. Moreover, lane_ids and is_final are also
* interpolated by zero order hold
* are resampled by spline interpolation, position z are resampled by linear interpolation,
* longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is
* resampled by linear interpolation. Orientation of the resampled path are calculated by a
* forward difference method based on the interpolated position x and y. Moreover, lane_ids
* and is_final are also interpolated by zero order hold
* @param input_path input path to resample
* @param resampled_interval resampling interval
* point
* @param resampled_interval resampling interval point
* @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and
* y. Otherwise, it uses spline interpolation
* y. Otherwise, it uses spline interpolation
* @param use_lerp_for_z If true, it uses linear interpolation to resample position z.
* Otherwise, it uses spline interpolation
* Otherwise, it uses spline interpolation
* @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
* @param resample_input_path_stop_point If true, resample closest stop point in input path
* @return resampled path
*/
Expand All @@ -106,42 +105,64 @@ autoware_auto_planning_msgs::msg::PathWithLaneId resamplePath(

/**
* @brief A resampling function for a path. Note that in a default setting, position xy are
* resampled by spline interpolation, position z are resampled by linear interpolation, longitudinal
* and lateral velocity are resampled by zero_order_hold, and heading rate is resampled by linear
* interpolation. Orientation of the resampled path are calculated by a forward difference method
* based on the interpolated position x and y.
* resampled by spline interpolation, position z are resampled by linear interpolation,
* longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is
* resampled by linear interpolation. Orientation of the resampled path are calculated by a
* forward difference method based on the interpolated position x and y.
* @param input_path input path to resample
* @param resampled_arclength arclength that contains length of each resampling points from initial
* point
* point
* @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and
* y. Otherwise, it uses spline interpolation
* y. Otherwise, it uses spline interpolation
* @param use_lerp_for_z If true, it uses linear interpolation to resample position z.
* Otherwise, it uses spline interpolation
* Otherwise, it uses spline interpolation
* @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
* @return resampled path
*/
autoware_auto_planning_msgs::msg::Path resamplePath(
const autoware_auto_planning_msgs::msg::Path & input_path,
const std::vector<double> & resampled_arclength, const bool use_lerp_for_xy = false,
const bool use_lerp_for_z = true, const bool use_zero_order_hold_for_v = true);

/**
* @brief A resampling function for a path. Note that in a default setting, position xy
* are resampled by spline interpolation, position z are resampled by linear interpolation,
* longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is
* resampled by linear interpolation. Orientation of the resampled path are calculated by a
* forward difference method based on the interpolated position x and y.
* @param input_path input path to resample
* @param resampled_interval resampling interval point
* @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and
* y. Otherwise, it uses spline interpolation
* @param use_lerp_for_z If true, it uses linear interpolation to resample position z.
* Otherwise, it uses spline interpolation
* @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
* @param resample_input_path_stop_point If true, resample closest stop point in input path
* @return resampled path
*/
autoware_auto_planning_msgs::msg::Path resamplePath(
const autoware_auto_planning_msgs::msg::Path & input_path, const double resample_interval,
const bool use_lerp_for_xy = false, const bool use_lerp_for_z = true,
const bool use_zero_order_hold_for_v = true, const bool resample_input_path_stop_point = true);

/**
* @brief A resampling function for a trajectory. Note that in a default setting, position xy are
* resampled by spline interpolation, position z are resampled by linear interpolation, twist
* informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate is
* resampled by linear interpolation. The rest of the category is resampled by linear interpolation.
* Orientation of the resampled path are calculated by a forward difference method based on the
* interpolated position x and y.
* resampled by spline interpolation, position z are resampled by linear interpolation, twist
* informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate
* is resampled by linear interpolation. The rest of the category is resampled by linear
* interpolation. Orientation of the resampled path are calculated by a forward difference
* method based on the interpolated position x and y.
* @param input_trajectory input trajectory to resample
* @param resampled_arclength arclength that contains length of each resampling points from initial
* point
* point
* @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and
* y. Otherwise, it uses spline interpolation
* y. Otherwise, it uses spline interpolation
* @param use_lerp_for_z If true, it uses linear interpolation to resample position z.
* Otherwise, it uses spline interpolation
* Otherwise, it uses spline interpolation
* @param use_zero_order_hold_for_twist If true, it uses zero_order_hold to resample
* longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation
* longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation
* @return resampled trajectory
*/
autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory(
Expand All @@ -151,22 +172,22 @@ autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory(

/**
* @brief A resampling function for a trajectory. This function resamples closest stop point,
* terminal point and points by resample interval. Note that in a default setting, position xy are
* resampled by spline interpolation, position z are resampled by linear interpolation, twist
* informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate is
* resampled by linear interpolation. The rest of the category is resampled by linear interpolation.
* Orientation of the resampled path are calculated by a forward difference method based on the
* interpolated position x and y.
* terminal point and points by resample interval. Note that in a default setting, position
* xy are resampled by spline interpolation, position z are resampled by linear interpolation, twist
* informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate
* is resampled by linear interpolation. The rest of the category is resampled by linear
* interpolation. Orientation of the resampled path are calculated by a forward difference
* method based on the interpolated position x and y.
* @param input_trajectory input trajectory to resample
* @param resampled_interval resampling interval
* @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and
* y. Otherwise, it uses spline interpolation
* y. Otherwise, it uses spline interpolation
* @param use_lerp_for_z If true, it uses linear interpolation to resample position z.
* Otherwise, it uses spline interpolation
* Otherwise, it uses spline interpolation
* @param use_zero_order_hold_for_twist If true, it uses zero_order_hold to resample
* longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation
* longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation
* @param resample_input_trajectory_stop_point If true, resample closest stop point in input
* trajectory
* trajectory
* @return resampled trajectory
*/
autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory(
Expand Down
Loading