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;
66 std::vector<std::string> joint_names_;
67 std::vector<std::string> command_interface_types_;
68 std::vector<std::string> state_interface_types_;
70 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_;
72 traj_msg_external_point_ptr_;
73 bool new_msg_ =
false;
74 rclcpp::Time start_time_;
75 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
76 trajectory_msgs::msg::JointTrajectoryPoint point_interp_;
78 std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
79 joint_position_command_interface_;
80 std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
81 joint_velocity_command_interface_;
82 std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
83 joint_position_state_interface_;
84 std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
85 joint_velocity_state_interface_;
88 std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> *>
89 command_interface_map_ = {
90 {
"position", &joint_position_command_interface_},
91 {
"velocity", &joint_velocity_command_interface_}};
94 std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>> *>
95 state_interface_map_ = {
96 {
"position", &joint_position_state_interface_},
97 {
"velocity", &joint_velocity_state_interface_}};