|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration | command_interface_configuration () const override |
| command_interface_configuration This controller requires the position command interfaces for the controlled joints
|
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration | state_interface_configuration () const override |
| command_interface_configuration This controller requires the position and velocity state interfaces for the controlled joints
|
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period) override |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC CallbackReturn | on_init () override |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &previous_state) override |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC CallbackReturn | on_error (const rclcpp_lifecycle::State &previous_state) override |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC CallbackReturn | on_shutdown (const rclcpp_lifecycle::State &previous_state) override |
|
CONTROLLER_INTERFACE_PUBLIC void | assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces) |
|
CONTROLLER_INTERFACE_PUBLIC void | release_interfaces () |
|
virtual CONTROLLER_INTERFACE_PUBLIC return_type | init (const std::string &controller_name) |
|
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp::Node > | get_node () |
|
template<typename ParameterT > |
auto | auto_declare (const std::string &name, const ParameterT &default_value) |
| Declare and initialize a parameter with a type.
|
|
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | configure () |
|
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | cleanup () |
|
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | deactivate () |
|
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | activate () |
|
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | shutdown () |
|
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | get_state () const |
|
CONTROLLER_INTERFACE_PUBLIC unsigned int | get_update_rate () const |
|
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC rclcpp_action::GoalResponse | goal_callback (const rclcpp_action::GoalUUID &uuid, std::shared_ptr< const FollowJTrajAction::Goal > goal) |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC rclcpp_action::CancelResponse | cancel_callback (const std::shared_ptr< rclcpp_action::ServerGoalHandle< FollowJTrajAction > > goal_handle) |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | feedback_setup_callback (std::shared_ptr< rclcpp_action::ServerGoalHandle< FollowJTrajAction > > goal_handle) |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | fill_partial_goal (std::shared_ptr< trajectory_msgs::msg::JointTrajectory > trajectory_msg) const |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | sort_to_local_joint_order (std::shared_ptr< trajectory_msgs::msg::JointTrajectory > trajectory_msg) |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool | validate_trajectory_msg (const trajectory_msgs::msg::JointTrajectory &trajectory) const |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | add_new_trajectory_msg (const std::shared_ptr< trajectory_msgs::msg::JointTrajectory > &traj_msg) |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool | validate_trajectory_point_field (size_t joint_names_size, const std::vector< double > &vector_field, const std::string &string_for_vector_field, size_t i, bool allow_empty) const |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | preempt_active_goal () |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | set_hold_position () |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool | reset () |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | publish_state (const JointTrajectoryPoint &desired_state, const JointTrajectoryPoint ¤t_state, const JointTrajectoryPoint &state_error) |
|
void | read_state_from_hardware (JointTrajectoryPoint &state) |
|
bool | read_state_from_command_interfaces (JointTrajectoryPoint &state) |
|
|
std::vector< std::string > | joint_names_ |
|
std::vector< std::string > | command_interface_types_ |
|
std::vector< std::string > | state_interface_types_ |
|
const std::vector< std::string > | allowed_interface_types_ |
|
bool | open_loop_control_ = false |
|
trajectory_msgs::msg::JointTrajectoryPoint | last_commanded_state_ |
|
InterfaceReferences< hardware_interface::LoanedCommandInterface > | joint_command_interface_ |
|
InterfaceReferences< hardware_interface::LoanedStateInterface > | joint_state_interface_ |
|
bool | has_velocity_state_interface_ = false |
|
bool | has_acceleration_state_interface_ = false |
|
bool | has_position_command_interface_ = false |
|
bool | has_velocity_command_interface_ = false |
|
bool | has_acceleration_command_interface_ = false |
|
bool | use_closed_loop_pid_adapter = false |
| If true, a velocity feedforward term plus corrective PID term is used.
|
|
bool | subscriber_is_active_ = false |
|
rclcpp::Subscription< trajectory_msgs::msg::JointTrajectory >::SharedPtr | joint_command_subscriber_ |
|
std::shared_ptr< Trajectory > * | traj_point_active_ptr_ = nullptr |
|
std::shared_ptr< Trajectory > | traj_external_point_ptr_ = nullptr |
|
std::shared_ptr< Trajectory > | traj_home_point_ptr_ = nullptr |
|
std::shared_ptr< trajectory_msgs::msg::JointTrajectory > | traj_msg_home_ptr_ = nullptr |
|
realtime_tools::RealtimeBuffer< std::shared_ptr< trajectory_msgs::msg::JointTrajectory > > | traj_msg_external_point_ptr_ |
|
bool | is_halted_ = true |
|
rclcpp::Publisher< ControllerStateMsg >::SharedPtr | publisher_ |
|
StatePublisherPtr | state_publisher_ |
|
rclcpp::Duration | state_publisher_period_ = rclcpp::Duration(20ms) |
|
rclcpp::Time | last_state_publish_time_ |
|
rclcpp_action::Server< FollowJTrajAction >::SharedPtr | action_server_ |
|
bool | allow_partial_joints_goal_ = false |
|
RealtimeGoalHandleBuffer | rt_active_goal_ |
| Currently active action goal, if any.
|
|
rclcpp::TimerBase::SharedPtr | goal_handle_timer_ |
|
rclcpp::Duration | action_monitor_period_ = rclcpp::Duration(50ms) |
|
SegmentTolerances | default_tolerances_ |
|
std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
|
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
|
std::shared_ptr< rclcpp::Node > | node_ |
|
rclcpp_lifecycle::State | lifecycle_state_ |
|
unsigned int | update_rate_ = 0 |
|