MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_pro_controllers::ControllerWithRobotModel Class Reference

#include <ros2_control_utils.hpp>

Inheritance diagram for moveit_pro_controllers::ControllerWithRobotModel:

Public Member Functions

 ControllerWithRobotModel ()=default
 
bool configurePlanningGroup (std::shared_ptr< rclcpp_lifecycle::LifecycleNode > node, const std::vector< std::string > &joints, const std::string_view &planning_group_name)
 
bool configureToolFrames (const std::string &sensor_frame, const std::string &ee_frame)
 
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 * getEndEffectorLink () const
 
const moveit::core::LinkModel * getSensorLink () const
 

Constructor & Destructor Documentation

◆ ControllerWithRobotModel()

moveit_pro_controllers::ControllerWithRobotModel::ControllerWithRobotModel ( )
default

Member Function Documentation

◆ configurePlanningGroup()

bool moveit_pro_controllers::ControllerWithRobotModel::configurePlanningGroup ( std::shared_ptr< rclcpp_lifecycle::LifecycleNode >  node,
const std::vector< std::string > &  joints,
const std::string_view &  planning_group_name 
)

◆ configureToolFrames()

bool moveit_pro_controllers::ControllerWithRobotModel::configureToolFrames ( const std::string &  sensor_frame,
const std::string &  ee_frame 
)

◆ getBaseLink()

const moveit::core::LinkModel * moveit_pro_controllers::ControllerWithRobotModel::getBaseLink ( ) const
inline

◆ getDofCount()

int moveit_pro_controllers::ControllerWithRobotModel::getDofCount ( ) const
inline

◆ getEndEffectorLink()

const moveit::core::LinkModel * moveit_pro_controllers::ControllerWithRobotModel::getEndEffectorLink ( ) const
inline

◆ getJointModelGroup()

const moveit::core::JointModelGroup * moveit_pro_controllers::ControllerWithRobotModel::getJointModelGroup ( ) const
inline

◆ getJointNames()

const std::vector< std::string > & moveit_pro_controllers::ControllerWithRobotModel::getJointNames ( ) const
inline

◆ getJointPositionLimits()

bool moveit_pro_controllers::ControllerWithRobotModel::getJointPositionLimits ( const std::vector< std::string > &  joint_names,
Eigen::VectorNd &  lower_position_limits,
Eigen::VectorNd &  upper_position_limits 
) const

◆ getPlanningGroupName()

const std::string & moveit_pro_controllers::ControllerWithRobotModel::getPlanningGroupName ( ) const
inline

◆ getRobotModel()

const moveit::core::RobotModel & moveit_pro_controllers::ControllerWithRobotModel::getRobotModel ( ) const
inline

◆ getRobotState() [1/2]

moveit::core::RobotState & moveit_pro_controllers::ControllerWithRobotModel::getRobotState ( )
inline

◆ getRobotState() [2/2]

const moveit::core::RobotState & moveit_pro_controllers::ControllerWithRobotModel::getRobotState ( ) const
inline

◆ getSensorLink()

const moveit::core::LinkModel * moveit_pro_controllers::ControllerWithRobotModel::getSensorLink ( ) const
inline

◆ loadRobotModel()

tl::expected< void, std::string > moveit_pro_controllers::ControllerWithRobotModel::loadRobotModel ( const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &  node)

◆ setRobotDescription()

void moveit_pro_controllers::ControllerWithRobotModel::setRobotDescription ( const std_msgs::msg::String::ConstSharedPtr  robot_description)

◆ setRobotDescriptionSemantic()

void moveit_pro_controllers::ControllerWithRobotModel::setRobotDescriptionSemantic ( const std_msgs::msg::String::ConstSharedPtr  robot_description_semantic)

◆ subscribeToRobotDescription()

void moveit_pro_controllers::ControllerWithRobotModel::subscribeToRobotDescription ( const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &  node)

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