chomp::ChompRobotModel Class Reference

Contains all the information needed for CHOMP planning. More...

#include <chomp_robot_model.h>

List of all members.

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

void attachedObjectCallback (const mapping_msgs::AttachedCollisionObjectConstPtr &attached_object)
 Callback for information about objects attached to the robot.
 ChompRobotModel ()
void generateAttachedObjectCollisionPoints (const motion_planning_msgs::RobotState *robot_state)
void generateLinkCollisionPoints ()
const
KDL::TreeFkSolverJointPosAxis
getForwardKinematicsSolver () const
const KDL::Tree * getKDLTree () const
 Gets the KDL tree.
void getLinkCollisionPoints (std::string link_name, std::vector< ChompCollisionPoint > &points)
double getMaxRadiusClearance () const
 Gets the max value of radius+clearance for all the collision points.
int getNumKDLJoints () const
 Gets the number of joints in the KDL tree.
const ChompPlanningGroupgetPlanningGroup (const std::string &group_name) const
 Gets the planning group corresponding to the group name.
const std::string & getReferenceFrame () const
const
planning_environment::RobotModels * 
getRobotModels () const
 Gets the planning_environment::RobotModels class.
bool init (planning_environment::CollisionSpaceMonitor *monitor_, std::string &reference_frame)
 Initializes the robot models for CHOMP.
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.
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.
void jointStateToArray (const sensor_msgs::JointState &joint_state, Eigen::MatrixXd::RowXpr joint_array)
void jointStateToArray (const sensor_msgs::JointState &joint_state, KDL::JntArray &joint_array)
const std::string kdlNumberToUrdfName (int kdl_number) const
 Gets the URDF joint name from the KDL joint number.
void populatePlanningGroupCollisionPoints ()
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 addCollisionPointsFromLink (const planning_models::KinematicState &state, std::string link_name, double clearance)
void getLinkInformation (const std::string link_name, std::vector< int > &active_joints, int &segment_number)

Private Attributes

ros::Subscriber attached_object_subscriber_
std::map< std::string,
mapping_msgs::AttachedCollisionObject > 
attached_objects_
double collision_clearance_default_
KDL::TreeFkSolverJointPosAxisfk_solver_
std::map< std::string,
std::string > 
joint_segment_mapping_
std::vector< std::string > kdl_number_to_urdf_name_
KDL::Tree kdl_tree_
std::map< std::string,
std::vector
< ChompCollisionPoint > > 
link_attached_object_collision_points_
std::map< std::string,
std::vector
< ChompCollisionPoint > > 
link_collision_points_
double max_radius_clearance_
planning_environment::CollisionSpaceMonitor * monitor_
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_

Detailed Description

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 57 of file chomp_robot_model.h.


Constructor & Destructor Documentation

chomp::ChompRobotModel::ChompRobotModel (  ) 

Definition at line 50 of file chomp_robot_model.cpp.

chomp::ChompRobotModel::~ChompRobotModel (  )  [virtual]

Definition at line 56 of file chomp_robot_model.cpp.


Member Function Documentation

void chomp::ChompRobotModel::addCollisionPointsFromLink ( const planning_models::KinematicState &  state,
std::string  link_name,
double  clearance 
) [private]

Definition at line 263 of file chomp_robot_model.cpp.

void chomp::ChompRobotModel::attachedObjectCallback ( const mapping_msgs::AttachedCollisionObjectConstPtr &  attached_object  ) 

Callback for information about objects attached to the robot.

void chomp::ChompRobotModel::generateAttachedObjectCollisionPoints ( const motion_planning_msgs::RobotState *  robot_state  ) 

Definition at line 403 of file chomp_robot_model.cpp.

void chomp::ChompRobotModel::generateLinkCollisionPoints (  ) 

Definition at line 369 of file chomp_robot_model.cpp.

const KDL::TreeFkSolverJointPosAxis * chomp::ChompRobotModel::getForwardKinematicsSolver (  )  const [inline]

Definition at line 267 of file chomp_robot_model.h.

const KDL::Tree * chomp::ChompRobotModel::getKDLTree (  )  const [inline]

Gets the KDL tree.

Definition at line 245 of file chomp_robot_model.h.

void chomp::ChompRobotModel::getLinkCollisionPoints ( std::string  link_name,
std::vector< ChompCollisionPoint > &  points 
)

Definition at line 354 of file chomp_robot_model.cpp.

void chomp::ChompRobotModel::getLinkInformation ( const std::string  link_name,
std::vector< int > &  active_joints,
int &  segment_number 
) [private]

Definition at line 226 of file chomp_robot_model.cpp.

double chomp::ChompRobotModel::getMaxRadiusClearance (  )  const [inline]

Gets the max value of radius+clearance for all the collision points.

Definition at line 348 of file chomp_robot_model.h.

int chomp::ChompRobotModel::getNumKDLJoints (  )  const [inline]

Gets the number of joints in the KDL tree.

Definition at line 240 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 226 of file chomp_robot_model.h.

const std::string & chomp::ChompRobotModel::getReferenceFrame (  )  const [inline]

Definition at line 272 of file chomp_robot_model.h.

const planning_environment::RobotModels * chomp::ChompRobotModel::getRobotModels (  )  const [inline]

Gets the planning_environment::RobotModels class.

Definition at line 235 of file chomp_robot_model.h.

bool chomp::ChompRobotModel::init ( planning_environment::CollisionSpaceMonitor *  monitor_,
std::string &  reference_frame 
)

Initializes the robot models for CHOMP.

Returns:
true if successful, false if not

Definition at line 60 of file chomp_robot_model.cpp.

template<typename T >
void chomp::ChompRobotModel::jointMsgToArray ( T &  msg_vector,
KDL::JntArray &  joint_array 
) [inline]

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 314 of file chomp_robot_model.h.

template<typename T >
void chomp::ChompRobotModel::jointMsgToArray ( T &  msg_vector,
Eigen::MatrixXd::RowXpr  joint_array 
) [inline]

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 302 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 336 of file chomp_robot_model.h.

void chomp::ChompRobotModel::jointStateToArray ( const sensor_msgs::JointState &  joint_state,
KDL::JntArray &  joint_array 
) [inline]

Definition at line 325 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.

Returns:
"" if the number does not have a name

Definition at line 259 of file chomp_robot_model.h.

void chomp::ChompRobotModel::populatePlanningGroupCollisionPoints (  ) 

Definition at line 487 of file chomp_robot_model.cpp.

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.

Returns:
-1 if the joint name is not found

Definition at line 250 of file chomp_robot_model.h.


Member Data Documentation

Attached object subscriber

Definition at line 190 of file chomp_robot_model.h.

std::map<std::string, mapping_msgs::AttachedCollisionObject> chomp::ChompRobotModel::attached_objects_ [private]

Map of links -> attached objects

Definition at line 205 of file chomp_robot_model.h.

Default clearance for all collision links

Definition at line 200 of file chomp_robot_model.h.

Forward kinematics solver for the tree

Definition at line 199 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 194 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 196 of file chomp_robot_model.h.

KDL::Tree chomp::ChompRobotModel::kdl_tree_ [private]

The KDL tree of the entire robot

Definition at line 192 of file chomp_robot_model.h.

Collision points associated with the objects attached to every link

Definition at line 203 of file chomp_robot_model.h.

std::map<std::string, std::vector<ChompCollisionPoint> > chomp::ChompRobotModel::link_collision_points_ [private]

Collision points associated with every link

Definition at line 202 of file chomp_robot_model.h.

Maximum value of radius + clearance for any of the collision points

Definition at line 204 of file chomp_robot_model.h.

planning_environment::CollisionSpaceMonitor* chomp::ChompRobotModel::monitor_ [private]

Definition at line 189 of file chomp_robot_model.h.

ros::NodeHandle chomp::ChompRobotModel::node_handle_ [private]

Definition at line 188 of file chomp_robot_model.h.

Total number of joints in the KDL tree

Definition at line 193 of file chomp_robot_model.h.

Planning group information

Definition at line 198 of file chomp_robot_model.h.

Reference frame for all kinematics operations

Definition at line 201 of file chomp_robot_model.h.

ros::NodeHandle chomp::ChompRobotModel::root_handle_ [private]

ROS Node handle

Definition at line 188 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 195 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 197 of file chomp_robot_model.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


chomp_motion_planner
Author(s): Mrinal Kalakrishnan / mail@mrinal.net
autogenerated on Fri Jan 11 09:52:45 2013