23 namespace std_ph = std::placeholders;
31 return "control/trajectory_control";
36 return carma_planning_msgs::msg::Plugin::CONTROL;
41 RCLCPP_DEBUG(rclcpp::get_logger(
"carma_guidance_plugins"),
"Received pose message");
47 RCLCPP_DEBUG(rclcpp::get_logger(
"carma_guidance_plugins"),
"Received twist message");
53 RCLCPP_DEBUG(rclcpp::get_logger(
"carma_guidance_plugins"),
"Received trajectory message");
60 current_pose_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>(
"current_pose", 1,
66 trajectory_plan_sub_ = create_subscription<carma_planning_msgs::msg::TrajectoryPlan>(std::string(get_name()) +
"/plan_trajectory", 1,
69 vehicle_cmd_pub_ = create_publisher<autoware_msgs::msg::ControlCommandStamped>(
"ctrl_raw", 1);
73 std::chrono::milliseconds(33),
rclcpp::TimerBase::SharedPtr command_timer_
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override final
std::string get_capability() override
Get the capability string representing this plugins capabilities Method must be overriden by extendin...
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override final
void current_pose_callback(geometry_msgs::msg::PoseStamped::UniquePtr msg)
boost::optional< geometry_msgs::msg::TwistStamped > current_twist_
The most recent velocity message received by this node.
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override final
virtual void current_trajectory_callback(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
Extending class provided method which can optionally handle trajectory plan callbacks.
uint8_t get_type() override final
Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum....
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > current_pose_sub_
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > current_trajectory_
The most recent trajectory received by this plugin.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > trajectory_plan_sub_
carma_ros2_utils::PubPtr< autoware_msgs::msg::ControlCommandStamped > vehicle_cmd_pub_
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override final
virtual autoware_msgs::msg::ControlCommandStamped generate_command()=0
Extending class provided method which should generate a command message which will be published to th...
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override final
ControlPlugin(const rclcpp::NodeOptions &)
ControlPlugin constructor.
void current_twist_callback(geometry_msgs::msg::TwistStamped::UniquePtr msg)
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override final
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > current_velocity_sub_
boost::optional< geometry_msgs::msg::PoseStamped > current_pose_
The most recent pose message received by this node.
PluginBaseNode provides default functionality for all carma guidance plugins. This includes basic sta...
virtual bool get_activation_status() final
Returns the activation status of this plugin. The plugins API callbacks will only be triggered when t...
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override