45 CONTROLLER_INTERFACE_PUBLIC
48 CONTROLLER_INTERFACE_PUBLIC
51 CONTROLLER_INTERFACE_PUBLIC
54 CONTROLLER_INTERFACE_PUBLIC
55 controller_interface::return_type
update(
56 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
58 CONTROLLER_INTERFACE_PUBLIC
59 controller_interface::CallbackReturn
on_init()
override;
61 CONTROLLER_INTERFACE_PUBLIC
62 controller_interface::CallbackReturn on_configure(
63 const rclcpp_lifecycle::State & previous_state)
override;
65 CONTROLLER_INTERFACE_PUBLIC
66 controller_interface::CallbackReturn on_activate(
67 const rclcpp_lifecycle::State & previous_state)
override;
69 CONTROLLER_INTERFACE_PUBLIC
70 controller_interface::CallbackReturn on_deactivate(
71 const rclcpp_lifecycle::State & previous_state)
override;
73 CONTROLLER_INTERFACE_PUBLIC
74 controller_interface::CallbackReturn on_cleanup(
75 const rclcpp_lifecycle::State & previous_state)
override;
77 CONTROLLER_INTERFACE_PUBLIC
78 controller_interface::CallbackReturn on_error(
79 const rclcpp_lifecycle::State & previous_state)
override;
81 CONTROLLER_INTERFACE_PUBLIC
82 controller_interface::CallbackReturn on_shutdown(
83 const rclcpp_lifecycle::State & previous_state)
override;
86 std::vector<std::string> joint_names_;
87 std::vector<std::string> command_interface_types_;
88 std::vector<std::string> state_interface_types_;
90 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_;
92 traj_msg_external_point_ptr_;
93 bool new_msg_ =
false;
94 rclcpp::Time start_time_;
95 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
96 trajectory_msgs::msg::JointTrajectoryPoint point_interp_;
98 std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
99 joint_position_command_interface_;
100 std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
101 joint_velocity_command_interface_;
102 std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
103 joint_position_state_interface_;
104 std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
105 joint_velocity_state_interface_;
108 std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> *>
109 command_interface_map_ = {
110 {
"position", &joint_position_command_interface_},
111 {
"velocity", &joint_velocity_command_interface_}};
114 std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>> *>
115 state_interface_map_ = {
116 {
"position", &joint_position_state_interface_},
117 {
"velocity", &joint_velocity_state_interface_}};