Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
trajectory_follower_wrapper_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2024 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
17
19{
20 namespace std_ph = std::placeholders;
21
23 : carma_guidance_plugins::ControlPlugin(options)
24 {
25 // Create initial config
27 config_.vehicle_response_lag = declare_parameter<double>("vehicle_response_lag", config_.vehicle_response_lag);
28 config_.vehicle_wheel_base = declare_parameter<double>("vehicle_wheel_base", config_.vehicle_wheel_base);
29 config_.incoming_cmd_time_threshold = declare_parameter<double>("incoming_cmd_time_threshold", config_.incoming_cmd_time_threshold);
30
31 }
32
33 rcl_interfaces::msg::SetParametersResult TrajectoryFollowerWrapperNode::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
34 {
35 auto error_double = update_params<double>({
36 {"vehicle_response_lag", config_.vehicle_response_lag},
37 {"vehicle_wheel_base", config_.vehicle_wheel_base},
38 {"incoming_cmd_time_threshold", config_.incoming_cmd_time_threshold}
39 }, parameters);
40
41 rcl_interfaces::msg::SetParametersResult result;
42
43 result.successful = !error_double;
44
45 return result;
46 }
47
48 carma_ros2_utils::CallbackReturn TrajectoryFollowerWrapperNode::on_configure_plugin()
49 {
50 // Reset config
52
53 // Load parameters
54 get_parameter<double>("vehicle_response_lag", config_.vehicle_response_lag);
55 get_parameter<double>("vehicle_wheel_base", config_.vehicle_wheel_base);
56 get_parameter<double>("incoming_cmd_time_threshold", config_.incoming_cmd_time_threshold);
57
58 RCLCPP_INFO_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "Loaded Params: " << config_);
59 // Register runtime parameter update callback
60 add_on_set_parameters_callback(std::bind(&TrajectoryFollowerWrapperNode::parameter_update_callback, this, std_ph::_1));
61
62 // NOTE: Currently, intra-process comms must be disabled for the following subscriber that is transient_local: https://github.com/ros2/rclcpp/issues/1753
63
64 rclcpp::SubscriptionOptions intra_proc_disabled;
65 intra_proc_disabled.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
66
67 auto sub_qos_transient_local = rclcpp::QoS(rclcpp::KeepAll()); // A subscriber with this QoS will store all messages that it has sent on the topic
68 sub_qos_transient_local.transient_local();
69 // Setup subscriber
70 control_cmd_sub_ = create_subscription<autoware_auto_msgs::msg::AckermannControlCommand>("trajectory_follower/control_cmd", sub_qos_transient_local,
71 std::bind(&TrajectoryFollowerWrapperNode::ackermann_control_cb, this, std::placeholders::_1),intra_proc_disabled);
72
73 // Setup publishers
74 autoware_traj_pub_ = create_publisher<autoware_auto_msgs::msg::Trajectory>("trajectory_follower/reference_trajectory", 10);
75 autoware_state_pub_ = create_publisher<autoware_auto_msgs::msg::VehicleKinematicState>("trajectory_follower/current_kinematic_state", 10);
76
77 // Setup timers to publish autoware compatible info (trajectory and state)
78 autoware_info_timer_ = create_timer(
79 get_clock(),
80 std::chrono::milliseconds(33), // Spin at 30 Hz per plugin API
82
83 // Return success if everthing initialized successfully
84 return CallbackReturn::SUCCESS;
85 }
86
87
89 {
90 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "In autoware info timer callback");
91
93 {
94 // generate and publish autoware kinematic state
95 auto autoware_state = convert_state(current_pose_.get(), current_twist_.get());
96 autoware_state_pub_->publish(autoware_state);
97
98 // generate and publish autoware trajectory
99 current_trajectory_.get().header.frame_id = autoware_state.header.frame_id;
101
102 autoware_traj_pub_->publish(autoware_traj_plan);
103
104 }
105 }
106
107 double TrajectoryFollowerWrapperNode::get_wheel_angle_rad_from_twist(const geometry_msgs::msg::TwistStamped& twist) const
108 {
109
110 if (std::abs(twist.twist.linear.x) < EPSILON )
111 {
112 return 0.0;
113 }
114
115 double steering_angle = std::atan2(twist.twist.angular.z * config_.vehicle_wheel_base, twist.twist.linear.x);
116 return steering_angle;
117 }
118
119 void TrajectoryFollowerWrapperNode::ackermann_control_cb(const autoware_auto_msgs::msg::AckermannControlCommand::SharedPtr msg)
120 {
121 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "In ackermann control callback");
123 }
124
125
126 autoware_auto_msgs::msg::VehicleKinematicState TrajectoryFollowerWrapperNode::convert_state(const geometry_msgs::msg::PoseStamped& pose, const geometry_msgs::msg::TwistStamped& twist) const
127 {
128 autoware_auto_msgs::msg::VehicleKinematicState state;
129 state.header = pose.header;
130 state.header.frame_id = "map";
131 state.state.x = pose.pose.position.x;
132 state.state.y = pose.pose.position.y;
133 state.state.z = pose.pose.position.z;
134 state.state.heading.real = pose.pose.orientation.w;
135 state.state.heading.imag = pose.pose.orientation.z;
136
137 state.state.front_wheel_angle_rad = get_wheel_angle_rad_from_twist(twist);
138 state.state.longitudinal_velocity_mps = twist.twist.linear.x;
139 state.state.lateral_velocity_mps = twist.twist.linear.y;
140 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "front_wheel_angle_rad: " << state.state.front_wheel_angle_rad);
141
142
143
144 return state;
145 }
146
147 autoware_msgs::msg::ControlCommandStamped TrajectoryFollowerWrapperNode::convert_cmd(const autoware_auto_msgs::msg::AckermannControlCommand& cmd) const
148 {
149 autoware_msgs::msg::ControlCommandStamped return_cmd;
150 return_cmd.header.stamp = cmd.stamp;
151
152 return_cmd.cmd.linear_acceleration = cmd.longitudinal.acceleration;
153 return_cmd.cmd.linear_velocity = cmd.longitudinal.speed;
154 return_cmd.cmd.steering_angle = cmd.lateral.steering_tire_angle;
155
156 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "generated command cmd.stamp: " << std::to_string(rclcpp::Time(cmd.stamp).seconds()));
157 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "generated command cmd.longitudinal.acceleration: " << cmd.longitudinal.acceleration);
158 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "generated command cmd.longitudinal.speed: " << cmd.longitudinal.speed);
159 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "generated command cmd.lateral.steering_tire_angle: " << cmd.lateral.steering_tire_angle);
160 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "generated command cmd.lateral.steering_tire_rotation_rate: " << cmd.lateral.steering_tire_rotation_rate);
161
162 return return_cmd;
163 }
164
165 autoware_msgs::msg::ControlCommandStamped TrajectoryFollowerWrapperNode::generate_command()
166 {
167 // process and save the trajectory
168 autoware_msgs::msg::ControlCommandStamped converted_cmd;
169
171 {
172 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "Insufficient data, empty control command generated");
173 return converted_cmd;
174 }
175
176
178 {
179 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("trajectory_follower_wrapper"), "Control Command is old, empty control command generated");
180 return converted_cmd;
181 }
182
183 converted_cmd = convert_cmd(received_ctrl_command_.value());
184
185 return converted_cmd;
186 }
187
188 bool TrajectoryFollowerWrapperNode::isControlCommandOld(const autoware_auto_msgs::msg::AckermannControlCommand& cmd) const
189 {
190 double difference = std::abs(this->now().seconds() - rclcpp::Time(cmd.stamp).seconds());
191
192 if (difference >= config_.incoming_cmd_time_threshold)
193 {
194 return true;
195 }
196
197 return false;
198 }
199
201 {
202 return true;
203 }
204
206 {
207 return "1.0";
208 }
209
210
211} // trajectory_follower_wrapper
212
213#include "rclcpp_components/register_node_macro.hpp"
214
215// Register the component with class_loader
boost::optional< geometry_msgs::msg::TwistStamped > current_twist_
The most recent velocity message received by this node.
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > current_trajectory_
The most recent trajectory received by this plugin.
boost::optional< geometry_msgs::msg::PoseStamped > current_pose_
The most recent pose message received by this node.
bool isControlCommandOld(const autoware_auto_msgs::msg::AckermannControlCommand &cmd) const
Check to see if the received control command recent or old.
autoware_msgs::msg::ControlCommandStamped convert_cmd(const autoware_auto_msgs::msg::AckermannControlCommand &cmd) const
convert autoware Ackermann control command to autoware stamped control command
carma_ros2_utils::PubPtr< autoware_auto_msgs::msg::Trajectory > autoware_traj_pub_
carma_ros2_utils::PubPtr< autoware_auto_msgs::msg::VehicleKinematicState > autoware_state_pub_
double get_wheel_angle_rad_from_twist(const geometry_msgs::msg::TwistStamped &twist) const
calculate wheel angle in rad from angular velocity in twist message
carma_ros2_utils::SubPtr< autoware_auto_msgs::msg::AckermannControlCommand > control_cmd_sub_
void ackermann_control_cb(const autoware_auto_msgs::msg::AckermannControlCommand::SharedPtr msg)
autoware's control subscription callback
void autoware_info_timer_callback()
Timer callback to spin at 30 hz and frequently publish autoware kinematic state and trajectory.
TrajectoryFollowerWrapperNode(const rclcpp::NodeOptions &options)
Node constructor.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback for dynamic parameter updates.
autoware_auto_msgs::msg::VehicleKinematicState convert_state(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist) const
convert vehicle's pose and twist messages to autoware kinematic state
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
std::optional< autoware_auto_msgs::msg::AckermannControlCommand > received_ctrl_command_
autoware_msgs::msg::ControlCommandStamped generate_command() override
Extending class provided method which should generate a command message which will be published to th...
std::string get_version_id() override
Returns the version id of this plugin.
carma_ros2_utils::CallbackReturn on_configure_plugin() override
This method should be used to load parameters and will be called on the configure state transition.
#define EPSILON
autoware_auto_msgs::msg::Trajectory process_trajectory_plan(const carma_planning_msgs::msg::TrajectoryPlan &tp, double vehicle_response_lag)
Given a carma type of trajectory_plan, generate autoware type of trajectory accounting for speed_lag ...
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
Stuct containing the algorithm configuration values for trajectory_follower_wrapper.