34 controller_interface::CallbackReturn
on_init()
override;
36 controller_interface::CallbackReturn on_configure(
37 const rclcpp_lifecycle::State & previous_state)
override;
39 controller_interface::CallbackReturn on_activate(
40 const rclcpp_lifecycle::State & previous_state)
override;
42 controller_interface::CallbackReturn on_deactivate(
43 const rclcpp_lifecycle::State & previous_state)
override;
45 controller_interface::return_type
update(
46 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
49 std::shared_ptr<motion_primitives_forward_controller::ParamListener> param_listener_;
50 motion_primitives_forward_controller::Params params_;
52 using ExecuteMotionAction = control_msgs::action::ExecuteMotionPrimitiveSequence;
53 rclcpp_action::Server<ExecuteMotionAction>::SharedPtr action_server_;
54 rclcpp_action::GoalResponse goal_received_callback(
55 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const ExecuteMotionAction::Goal> goal);
56 rclcpp_action::CancelResponse goal_cancelled_callback(
57 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteMotionAction>> goal_handle);
58 void goal_accepted_callback(
59 std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteMotionAction>> goal_handle);