Contains all the information needed for CHOMP planning. More...
#include <chomp_robot_model.h>
Classes | |
| struct | ChompJoint | 
| Contains information about a single joint for CHOMP planning.  More... | |
| struct | ChompPlanningGroup | 
| Contains information about a planning group.  More... | |
Public Member Functions | |
| ChompRobotModel () | |
| void | getActiveJointInformation (const std::string &link_name, std::vector< int > &active_joints, int &segment_number) | 
| const  KDL::TreeFkSolverJointPosAxis *  | getForwardKinematicsSolver () const | 
| const KDL::Tree * | getKDLTree () const | 
| Gets the KDL tree.   | |
| int | getNumKDLJoints () const | 
| Gets the number of joints in the KDL tree.   | |
| const ChompPlanningGroup * | getPlanningGroup (const std::string &group_name) const | 
| Gets the planning group corresponding to the group name.   | |
| const std::string & | getReferenceFrame () const | 
| bool | init (const planning_environment::CollisionModels *model) | 
| Initializes the robot models for CHOMP.   | |
| template<typename T > | |
| void | jointMsgToArray (T &msg_vector, Eigen::MatrixXd::RowXpr joint_array) | 
| Takes in an std::vector of joint value messages, and writes them out into the KDL joint array.   | |
| template<typename T > | |
| void | jointMsgToArray (T &msg_vector, KDL::JntArray &joint_array) | 
| Takes in an std::vector of joint value messages, and writes them out into the KDL joint array.   | |
| void | jointStateToArray (const sensor_msgs::JointState &joint_state, KDL::JntArray &joint_array) | 
| void | jointStateToArray (const sensor_msgs::JointState &joint_state, Eigen::MatrixXd::RowXpr joint_array) | 
| const std::string | kdlNumberToUrdfName (int kdl_number) const | 
| Gets the URDF joint name from the KDL joint number.   | |
| void | publishCollisionPoints (ros::Publisher &vis_marker) | 
| int | urdfNameToKdlNumber (const std::string &urdf_name) const | 
| Gets the KDL joint number from the URDF joint name.   | |
| virtual | ~ChompRobotModel () | 
Private Member Functions | |
| void | getLinkInformation (const std::string link_name, std::vector< int > &active_joints, int &segment_number) | 
Private Attributes | |
| KDL::TreeFkSolverJointPosAxis * | fk_solver_ | 
| std::map< std::string,  std::string >  | joint_segment_mapping_ | 
| std::vector< std::string > | kdl_number_to_urdf_name_ | 
| KDL::Tree | kdl_tree_ | 
| double | max_radius_clearance_ | 
| ros::NodeHandle | node_handle_ | 
| int | num_kdl_joints_ | 
| std::map< std::string,  ChompPlanningGroup >  | planning_groups_ | 
| std::string | reference_frame_ | 
| ros::NodeHandle | root_handle_ | 
| std::map< std::string,  std::string >  | segment_joint_mapping_ | 
| std::map< std::string, int > | urdf_name_to_kdl_number_ | 
Contains all the information needed for CHOMP planning.
Initializes the robot models for CHOMP from the "robot_description" parameter, in the same way that planning_environment::RobotModels does it.
Definition at line 66 of file chomp_robot_model.h.
Definition at line 50 of file chomp_robot_model.cpp.
| chomp::ChompRobotModel::~ChompRobotModel | ( | ) |  [virtual] | 
        
Definition at line 55 of file chomp_robot_model.cpp.
| void chomp::ChompRobotModel::getActiveJointInformation | ( | const std::string & | link_name, | 
| std::vector< int > & | active_joints, | ||
| int & | segment_number | ||
| ) | 
Definition at line 244 of file chomp_robot_model.cpp.
| const KDL::TreeFkSolverJointPosAxis * chomp::ChompRobotModel::getForwardKinematicsSolver | ( | ) |  const [inline] | 
        
Definition at line 236 of file chomp_robot_model.h.
| const KDL::Tree * chomp::ChompRobotModel::getKDLTree | ( | ) |  const [inline] | 
        
Gets the KDL tree.
Definition at line 214 of file chomp_robot_model.h.
| void chomp::ChompRobotModel::getLinkInformation | ( | const std::string | link_name, | 
| std::vector< int > & | active_joints, | ||
| int & | segment_number | ||
| ) |  [private] | 
        
Definition at line 219 of file chomp_robot_model.cpp.
| int chomp::ChompRobotModel::getNumKDLJoints | ( | ) |  const [inline] | 
        
Gets the number of joints in the KDL tree.
Definition at line 209 of file chomp_robot_model.h.
| const ChompRobotModel::ChompPlanningGroup * chomp::ChompRobotModel::getPlanningGroup | ( | const std::string & | group_name | ) |  const [inline] | 
        
Gets the planning group corresponding to the group name.
Definition at line 200 of file chomp_robot_model.h.
| const std::string & chomp::ChompRobotModel::getReferenceFrame | ( | ) |  const [inline] | 
        
Definition at line 241 of file chomp_robot_model.h.
| bool chomp::ChompRobotModel::init | ( | const planning_environment::CollisionModels * | model | ) | 
Initializes the robot models for CHOMP.
Definition at line 59 of file chomp_robot_model.cpp.
| void chomp::ChompRobotModel::jointMsgToArray | ( | T & | msg_vector, | 
| Eigen::MatrixXd::RowXpr | joint_array | ||
| ) | 
Takes in an std::vector of joint value messages, and writes them out into the KDL joint array.
The template typename T needs to be an std::vector of some message which has an std::string "joint_name" and a double array/vector "value".
Names to KDL joint index mappings are performed using the given ChompRobotModel.
Definition at line 271 of file chomp_robot_model.h.
| void chomp::ChompRobotModel::jointMsgToArray | ( | T & | msg_vector, | 
| KDL::JntArray & | joint_array | ||
| ) | 
Takes in an std::vector of joint value messages, and writes them out into the KDL joint array.
The template typename T needs to be an std::vector of some message which has an std::string "joint_name" and a double array/vector "value".
Names to KDL joint index mappings are performed using the given ChompRobotModel.
Definition at line 283 of file chomp_robot_model.h.
| void chomp::ChompRobotModel::jointStateToArray | ( | const sensor_msgs::JointState & | joint_state, | 
| KDL::JntArray & | joint_array | ||
| ) |  [inline] | 
        
Definition at line 294 of file chomp_robot_model.h.
| void chomp::ChompRobotModel::jointStateToArray | ( | const sensor_msgs::JointState & | joint_state, | 
| Eigen::MatrixXd::RowXpr | joint_array | ||
| ) |  [inline] | 
        
Definition at line 305 of file chomp_robot_model.h.
| const std::string chomp::ChompRobotModel::kdlNumberToUrdfName | ( | int | kdl_number | ) |  const [inline] | 
        
Gets the URDF joint name from the KDL joint number.
Definition at line 228 of file chomp_robot_model.h.
| void chomp::ChompRobotModel::publishCollisionPoints | ( | ros::Publisher & | vis_marker | ) | 
| int chomp::ChompRobotModel::urdfNameToKdlNumber | ( | const std::string & | urdf_name | ) |  const [inline] | 
        
Gets the KDL joint number from the URDF joint name.
Definition at line 219 of file chomp_robot_model.h.
Forward kinematics solver for the tree
Definition at line 188 of file chomp_robot_model.h.
std::map<std::string, std::string> chomp::ChompRobotModel::joint_segment_mapping_ [private] | 
        
Joint -> Segment mapping for KDL tree
Definition at line 183 of file chomp_robot_model.h.
std::vector<std::string> chomp::ChompRobotModel::kdl_number_to_urdf_name_ [private] | 
        
Mapping from KDL joint number to URDF joint name
Definition at line 185 of file chomp_robot_model.h.
KDL::Tree chomp::ChompRobotModel::kdl_tree_ [private] | 
        
The KDL tree of the entire robot
Definition at line 181 of file chomp_robot_model.h.
double chomp::ChompRobotModel::max_radius_clearance_ [private] | 
        
Maximum value of radius + clearance for any of the collision points
Definition at line 190 of file chomp_robot_model.h.
Definition at line 179 of file chomp_robot_model.h.
int chomp::ChompRobotModel::num_kdl_joints_ [private] | 
        
Total number of joints in the KDL tree
Definition at line 182 of file chomp_robot_model.h.
std::map<std::string, ChompPlanningGroup> chomp::ChompRobotModel::planning_groups_ [private] | 
        
Planning group information
Definition at line 187 of file chomp_robot_model.h.
std::string chomp::ChompRobotModel::reference_frame_ [private] | 
        
Reference frame for all kinematics operations
Definition at line 189 of file chomp_robot_model.h.
ROS Node handle
Definition at line 179 of file chomp_robot_model.h.
std::map<std::string, std::string> chomp::ChompRobotModel::segment_joint_mapping_ [private] | 
        
Segment -> Joint mapping for KDL tree
Definition at line 184 of file chomp_robot_model.h.
std::map<std::string, int> chomp::ChompRobotModel::urdf_name_to_kdl_number_ [private] | 
        
Mapping from URDF joint name to KDL joint number
Definition at line 186 of file chomp_robot_model.h.