51 controller_interface::return_type
update(
52 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
54 controller_interface::CallbackReturn
on_init()
override;
56 controller_interface::CallbackReturn on_configure(
57 const rclcpp_lifecycle::State & previous_state)
override;
59 controller_interface::CallbackReturn on_activate(
60 const rclcpp_lifecycle::State & previous_state)
override;
62 controller_interface::CallbackReturn on_deactivate(
63 const rclcpp_lifecycle::State & previous_state)
override;
65 controller_interface::CallbackReturn on_cleanup(
66 const rclcpp_lifecycle::State & previous_state)
override;
68 controller_interface::CallbackReturn on_error(
69 const rclcpp_lifecycle::State & previous_state)
override;
71 controller_interface::CallbackReturn on_shutdown(
72 const rclcpp_lifecycle::State & previous_state)
override;
75 std::vector<std::string> joint_names_;
76 std::vector<std::string> command_interface_types_;
77 std::vector<std::string> state_interface_types_;
79 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_;
81 traj_msg_external_point_ptr_;
82 bool new_msg_ =
false;
83 rclcpp::Time start_time_;
84 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
85 trajectory_msgs::msg::JointTrajectoryPoint point_interp_;
87 std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
88 joint_position_command_interface_;
89 std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
90 joint_velocity_command_interface_;
91 std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
92 joint_position_state_interface_;
93 std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
94 joint_velocity_state_interface_;
97 std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> *>
98 command_interface_map_ = {
99 {
"position", &joint_position_command_interface_},
100 {
"velocity", &joint_velocity_command_interface_}};
103 std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>> *>
104 state_interface_map_ = {
105 {
"position", &joint_position_state_interface_},
106 {
"velocity", &joint_velocity_state_interface_}};