|
| | JointVelocityController () |
| |
| controller_interface::InterfaceConfiguration | command_interface_configuration () const override |
| |
| controller_interface::InterfaceConfiguration | state_interface_configuration () const override |
| |
| CallbackReturn | on_init () override |
| |
| CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
| |
| CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
| |
| CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
| |
| controller_interface::return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period) override |
| |
| const joint_velocity_controller::Params & | getControllerParameters () const |
| |
| joint_velocity_controller::Params & | getControllerParameters () |
| |
| const JointVelocityParameters & | getJointVelocityParameters () const |
| |
| ExecutionState | getControllerState () const |
| |
| const TimedJointState & | getLastCommandedState () const |
| |
| void | overrideJointPositionLimits (const Eigen::VectorNd &lower_limits, const Eigen::VectorNd &upper_limits) |
| |
| | ControllerWithRobotModel ()=default |
| |
| bool | configurePlanningGroup (const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node, const std::vector< std::string > &joints, const std::string_view &planning_group_name, bool chain_required=true) |
| |
| bool | configureToolFrames (const std::string &controller_name, const std::vector< std::string > &sensor_frames, const std::vector< std::string > &ee_frames) |
| |
| void | subscribeToRobotDescription (const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node) |
| |
| tl::expected< void, std::string > | loadRobotModel (const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node) |
| |
| void | setRobotDescription (const std_msgs::msg::String::ConstSharedPtr robot_description) |
| |
| void | setRobotDescriptionSemantic (const std_msgs::msg::String::ConstSharedPtr robot_description_semantic) |
| |
| bool | getJointPositionLimits (const std::vector< std::string > &joint_names, Eigen::VectorNd &lower_position_limits, Eigen::VectorNd &upper_position_limits) const |
| |
| const moveit::core::RobotModel & | getRobotModel () const |
| |
| const moveit::core::RobotState & | getRobotState () const |
| |
| moveit::core::RobotState & | getRobotState () |
| |
| const std::string & | getPlanningGroupName () const |
| |
| const std::vector< std::string > & | getJointNames () const |
| |
| int | getDofCount () const |
| |
| const moveit::core::JointModelGroup * | getJointModelGroup () const |
| |
| const moveit::core::LinkModel * | getBaseLink () const |
| |
| const moveit::core::LinkModel * | getFirstEndEffectorLink () const |
| |
| std::span< moveit::core::LinkModel const *const > | getEndEffectorLinks () const |
| |
| const moveit::core::LinkModel * | getFirstSensorLink () const |
| |
| std::span< moveit::core::LinkModel const *const > | getSensorLinks () const |
| |