ros2_control - rolling
Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
joint_trajectory_controller::JointTrajectoryController Class Reference
Inheritance diagram for joint_trajectory_controller::JointTrajectoryController:
Inheritance graph
[legend]
Collaboration diagram for joint_trajectory_controller::JointTrajectoryController:
Collaboration graph
[legend]

Public Member Functions

JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
 command_interface_configuration
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
 command_interface_configuration
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
 Extending interface with initialization method which is individual for each controller. More...
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterfaceexport_state_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterfaceexport_reference_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode (bool chained_mode) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const final
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
virtual CONTROLLER_INTERFACE_PUBLIC void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 Method that assigns the Loaned interfaces to the controller. More...
 
virtual CONTROLLER_INTERFACE_PUBLIC void release_interfaces ()
 Method that releases the Loaned interfaces from the controller. More...
 
CONTROLLER_INTERFACE_PUBLIC return_type init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options)
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > get_node () const
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state () const
 
CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate () const
 
CONTROLLER_INTERFACE_PUBLIC bool is_async () const
 
CONTROLLER_INTERFACE_PUBLIC const std::string & get_robot_description () const
 
virtual CONTROLLER_INTERFACE_PUBLIC rclcpp::NodeOptions define_custom_node_options () const
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type. More...
 

Protected Types

template<typename T >
using InterfaceReferences = std::vector< std::vector< std::reference_wrapper< T > >>
 
using PidPtr = std::shared_ptr< control_toolbox::Pid >
 
using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState
 
using StatePublisher = realtime_tools::RealtimePublisher< ControllerStateMsg >
 
using StatePublisherPtr = std::unique_ptr< StatePublisher >
 
using FollowJTrajAction = control_msgs::action::FollowJointTrajectory
 
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle< FollowJTrajAction >
 
using RealtimeGoalHandlePtr = std::shared_ptr< RealtimeGoalHandle >
 
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer< RealtimeGoalHandlePtr >
 
using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint
 

Protected Member Functions

JOINT_TRAJECTORY_CONTROLLER_PUBLIC void topic_callback (const std::shared_ptr< trajectory_msgs::msg::JointTrajectory > msg)
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC rclcpp_action::GoalResponse goal_received_callback (const rclcpp_action::GoalUUID &uuid, std::shared_ptr< const FollowJTrajAction::Goal > goal)
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC rclcpp_action::CancelResponse goal_cancelled_callback (const std::shared_ptr< rclcpp_action::ServerGoalHandle< FollowJTrajAction >> goal_handle)
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void goal_accepted_callback (std::shared_ptr< rclcpp_action::ServerGoalHandle< FollowJTrajAction >> goal_handle)
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void compute_error_for_joint (JointTrajectoryPoint &error, const size_t index, const JointTrajectoryPoint &current, const JointTrajectoryPoint &desired) const
 
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) const
 
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 std::shared_ptr< trajectory_msgs::msg::JointTrajectory > set_hold_position ()
 set the current position with zero velocity and acceleration as new command
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC std::shared_ptr< trajectory_msgs::msg::JointTrajectory > set_success_trajectory_point ()
 set last trajectory point to be repeated at success More...
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool reset ()
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool has_active_trajectory () const
 
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void publish_state (const rclcpp::Time &time, const JointTrajectoryPoint &desired_state, const JointTrajectoryPoint &current_state, const JointTrajectoryPoint &state_error)
 
void read_state_from_state_interfaces (JointTrajectoryPoint &state)
 
bool read_state_from_command_interfaces (JointTrajectoryPoint &state)
 
bool read_commands_from_command_interfaces (JointTrajectoryPoint &commands)
 
void query_state_service (const std::shared_ptr< control_msgs::srv::QueryTrajectoryState::Request > request, std::shared_ptr< control_msgs::srv::QueryTrajectoryState::Response > response)
 

Protected Attributes

const std::vector< std::string > allowed_interface_types_
 
trajectory_msgs::msg::JointTrajectoryPoint state_current_
 
trajectory_msgs::msg::JointTrajectoryPoint command_current_
 
trajectory_msgs::msg::JointTrajectoryPoint state_desired_
 
trajectory_msgs::msg::JointTrajectoryPoint state_error_
 
size_t dof_
 
std::vector< std::string > command_joint_names_
 
std::shared_ptr< ParamListener > param_listener_
 
Params params_
 
trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_
 
interpolation_methods::InterpolationMethod interpolation_method_
 Specify interpolation method. Default to splines. More...
 
InterfaceReferences< hardware_interface::LoanedCommandInterfacejoint_command_interface_
 
InterfaceReferences< hardware_interface::LoanedStateInterfacejoint_state_interface_
 
bool has_position_state_interface_ = false
 
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 has_effort_command_interface_ = false
 
bool use_closed_loop_pid_adapter_ = false
 If true, a velocity feedforward term plus corrective PID term is used.
 
std::vector< PidPtr > pids_
 
std::vector< double > ff_velocity_scale_
 
std::vector< bool > joints_angle_wraparound_
 
std::vector< double > tmp_command_
 
double cmd_timeout_
 
realtime_tools::RealtimeBuffer< bool > rt_is_holding_
 
bool subscriber_is_active_ = false
 
rclcpp::Subscription< trajectory_msgs::msg::JointTrajectory >::SharedPtr joint_command_subscriber_
 
rclcpp::Service< control_msgs::srv::QueryTrajectoryState >::SharedPtr query_state_srv_
 
std::shared_ptr< Trajectorytraj_external_point_ptr_ = nullptr
 
realtime_tools::RealtimeBuffer< std::shared_ptr< trajectory_msgs::msg::JointTrajectory > > traj_msg_external_point_ptr_
 
std::shared_ptr< trajectory_msgs::msg::JointTrajectory > hold_position_msg_ptr_ = nullptr
 
rclcpp::Publisher< ControllerStateMsg >::SharedPtr publisher_
 
StatePublisherPtr state_publisher_
 
rclcpp_action::Server< FollowJTrajAction >::SharedPtr action_server_
 
RealtimeGoalHandleBuffer rt_active_goal_
 Currently active action goal, if any.
 
realtime_tools::RealtimeBuffer< bool > rt_has_pending_goal_
 Is there a pending action goal?
 
rclcpp::TimerBase::SharedPtr goal_handle_timer_
 
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms)
 
SegmentTolerances default_tolerances_
 
realtime_tools::RealtimeBuffer< SegmentTolerancesactive_tolerances_
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 

Member Function Documentation

◆ compute_error_for_joint()

void joint_trajectory_controller::JointTrajectoryController::compute_error_for_joint ( JointTrajectoryPoint &  error,
const size_t  index,
const JointTrajectoryPoint &  current,
const JointTrajectoryPoint &  desired 
) const
protected

Computes the error for a specific joint in the trajectory.

Parameters
[out]errorThe computed error for the joint.
[in]indexThe index of the joint in the trajectory.
[in]currentThe current state of the joints.
[in]desiredThe desired state of the joints.

◆ on_init()

controller_interface::CallbackReturn joint_trajectory_controller::JointTrajectoryController::on_init ( )
overridevirtual

Extending interface with initialization method which is individual for each controller.

initialize the URDF model and update the joint angles wraparound vector

Implements controller_interface::ControllerInterfaceBase.

◆ read_state_from_command_interfaces()

bool joint_trajectory_controller::JointTrajectoryController::read_state_from_command_interfaces ( JointTrajectoryPoint &  state)
protected

Assign values from the command interfaces as state. This is only possible if command AND state interfaces exist for the same type, therefore needs check for both.

Parameters
[out]stateto be filled with values from command interfaces.
Returns
true if all interfaces exists and contain non-NaN values, false otherwise.

◆ set_success_trajectory_point()

std::shared_ptr< trajectory_msgs::msg::JointTrajectory > joint_trajectory_controller::JointTrajectoryController::set_success_trajectory_point ( )
protected

set last trajectory point to be repeated at success

no matter if it has nonzero velocity or acceleration

◆ update()

controller_interface::return_type joint_trajectory_controller::JointTrajectoryController::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ControllerInterfaceBase.

Member Data Documentation

◆ allowed_interface_types_

const std::vector<std::string> joint_trajectory_controller::JointTrajectoryController::allowed_interface_types_
protected
Initial value:
= {
}
constexpr char HW_IF_EFFORT[]
Constant defining effort interface name.
Definition: hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface name.
Definition: hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition: hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition: hardware_interface_type_values.hpp:21

◆ interpolation_method_

interpolation_methods::InterpolationMethod joint_trajectory_controller::JointTrajectoryController::interpolation_method_
protected
Initial value:
{
interpolation_methods::DEFAULT_INTERPOLATION}

Specify interpolation method. Default to splines.

◆ joint_command_subscriber_

rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_trajectory_controller::JointTrajectoryController::joint_command_subscriber_
protected
Initial value:
=
nullptr

The documentation for this class was generated from the following files: