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.hpp
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 */
16
17#pragma once
18
19#include <rclcpp/rclcpp.hpp>
20#include <carma_planning_msgs/msg/trajectory_plan.hpp>
22#include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
23#include <autoware_auto_msgs/msg/vehicle_control_command.hpp>
24#include <autoware_auto_msgs/msg/trajectory.hpp>
25#include <autoware_auto_msgs/msg/ackermann_control_command.hpp>
26#include <gtest/gtest_prod.h>
29#include <optional>
31
32constexpr double EPSILON = 0.0001;
33
35{
36
38 {
39
40 private:
41 // Subscribers
42 carma_ros2_utils::SubPtr<autoware_auto_msgs::msg::AckermannControlCommand> control_cmd_sub_;
43
44 // Publishers
45 carma_ros2_utils::PubPtr<autoware_auto_msgs::msg::Trajectory> autoware_traj_pub_;
46 carma_ros2_utils::PubPtr<autoware_auto_msgs::msg::VehicleKinematicState> autoware_state_pub_;
47
48 // Timers
49 rclcpp::TimerBase::SharedPtr autoware_info_timer_;
50
51 // Received Control Command
52 std::optional<autoware_auto_msgs::msg::AckermannControlCommand> received_ctrl_command_;
53
54 public:
55
59 explicit TrajectoryFollowerWrapperNode(const rclcpp::NodeOptions& options);
60
64 rcl_interfaces::msg::SetParametersResult
65 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
66
71
75 void ackermann_control_cb(const autoware_auto_msgs::msg::AckermannControlCommand::SharedPtr msg);
76
80 bool isControlCommandOld(const autoware_auto_msgs::msg::AckermannControlCommand& cmd) const;
81
82 // Node configuration
84
85 //CONVERSIONS
86
90 autoware_auto_msgs::msg::VehicleKinematicState convert_state(const geometry_msgs::msg::PoseStamped& pose, const geometry_msgs::msg::TwistStamped& twist) const;
91
95 autoware_msgs::msg::ControlCommandStamped convert_cmd(const autoware_auto_msgs::msg::AckermannControlCommand& cmd) const;
96
100 double get_wheel_angle_rad_from_twist(const geometry_msgs::msg::TwistStamped& twist) const;
101
102
103
105 // Overrides
107 autoware_msgs::msg::ControlCommandStamped generate_command() override;
108
109 bool get_availability() override;
110
111 std::string get_version_id() override;
112
116 carma_ros2_utils::CallbackReturn on_configure_plugin() override;
117
118 FRIEND_TEST(TesttrajectoryFollowerWrapper, TestControlCallback);
119 FRIEND_TEST(TesttrajectoryFollowerWrapper, TestThreshold);
120
121 };
122
123} // trajectory_follower_wrapper
ControlPlugin base class which can be extended by user provided plugins which wish to implement the C...
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
FRIEND_TEST(TesttrajectoryFollowerWrapper, TestThreshold)
FRIEND_TEST(TesttrajectoryFollowerWrapper, TestControlCallback)
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.
Stuct containing the algorithm configuration values for trajectory_follower_wrapper.
constexpr double EPSILON