ros2_control - galactic
Loading...
Searching...
No Matches
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 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
 
- Public Member Functions inherited from controller_interface::ControllerInterface
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
 

Protected Types

template<typename T >
using InterfaceReferences = std::vector< std::vector< std::reference_wrapper< T > > >
 
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 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 &current_state, const JointTrajectoryPoint &state_error)
 
void read_state_from_hardware (JointTrajectoryPoint &state)
 
bool read_state_from_command_interfaces (JointTrajectoryPoint &state)
 

Protected Attributes

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::LoanedCommandInterfacejoint_command_interface_
 
InterfaceReferences< hardware_interface::LoanedStateInterfacejoint_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< Trajectorytraj_external_point_ptr_ = nullptr
 
std::shared_ptr< Trajectorytraj_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_
 
- Protected Attributes inherited from controller_interface::ControllerInterface
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 
std::shared_ptr< rclcpp::Node > node_
 
rclcpp_lifecycle::State lifecycle_state_
 
unsigned int update_rate_ = 0
 

Member Function Documentation

◆ command_interface_configuration()

controller_interface::InterfaceConfiguration joint_trajectory_controller::JointTrajectoryController::command_interface_configuration ( ) const
overridevirtual

command_interface_configuration This controller requires the position command interfaces for the controlled joints

Implements controller_interface::ControllerInterface.

◆ on_init()

CallbackReturn joint_trajectory_controller::JointTrajectoryController::on_init ( )
overridevirtual

◆ state_interface_configuration()

controller_interface::InterfaceConfiguration joint_trajectory_controller::JointTrajectoryController::state_interface_configuration ( ) const
overridevirtual

command_interface_configuration This controller requires the position and velocity state interfaces for the controlled joints

Implements controller_interface::ControllerInterface.

◆ update()

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

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.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition hardware_interface_type_values.hpp:21

◆ joint_command_subscriber_

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

◆ open_loop_control_

bool joint_trajectory_controller::JointTrajectoryController::open_loop_control_ = false
protected

Run he controller in open-loop, i.e., read hardware states only when starting controller. This is useful when robot is not exactly following the commanded trajectory.


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