rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
rapid Namespace Reference

Namespaces

 db
 
 fetch
 
 manipulation
 
 perception
 
 pr2
 
 sound
 
 utils
 
 viz
 

Classes

class  MoveItPlanningScene
 Simple interface to the MoveIt planning scene monitor. More...
 
class  PointCloudCameraInterface
 Interface for a camera that outputs point clouds. More...
 
class  JointStateReader
 Tracks the latest joint states. More...
 
class  PointCloudCamera
 Gets point cloud and camera pose. More...
 
class  RecordedPointCloudCamera
 A simulated camera that loads data from a bag file. More...
 
class  RosoutTestHelper
 
class  Degrees
 Type for angles measured in degrees. More...
 
class  Radians
 Type for angles measured in radians. More...
 
class  DragBoxMarker
 An interactive marker for a box with draggable sides. More...
 

Typedefs

typedef pcl::PointXYZ PointP
 
typedef pcl::PointXYZRGB PointC
 
typedef pcl::PointCloud
< pcl::PointXYZ > 
PointCloudP
 
typedef pcl::PointCloud
< pcl::PointXYZRGB > 
PointCloudC
 

Functions

bool AreObbsInCollision (const geometry_msgs::Pose &pose1, const geometry_msgs::Vector3 &scale1, const geometry_msgs::Pose &pose2, const geometry_msgs::Vector3 &scale2)
 Returns true if the given oriented bounding boxes are colliding. More...
 
fcl::OBB BoxToOBB (const geometry_msgs::Pose &pose, const geometry_msgs::Vector3 &scale)
 Returns an fcl::OBB from a Pose and Vector3 message. More...
 
bool IsSuccess (const moveit::planning_interface::MoveItErrorCode &error_code)
 Returns true if the error code corresponds to success. More...
 
bool IsSuccess (const moveit_msgs::MoveItErrorCodes &error_code)
 Returns true if the error code corresponds to success. More...
 
std::string ErrorString (const moveit::planning_interface::MoveItErrorCode &error_code)
 Returns a string describing the given MoveIt error code. More...
 
std::string ErrorString (const moveit_msgs::MoveItErrorCodes &error_code)
 Returns a string describing the given MoveIt error code. More...
 
std::string GetStringParamOrThrow (const std::string &name)
 Gets a string from the parameter server. More...
 
double GetDoubleParamOrThrow (const std::string &name)
 Gets a double from the parameter server. More...
 
float GetFloatParamOrThrow (const std::string &name)
 Gets a float from the parameter server. More...
 
int GetIntParamOrThrow (const std::string &name)
 Gets an int from the parameter server. More...
 
bool GetBoolParamOrThrow (const std::string &name)
 Gets a bool from the parameter server. More...
 
XmlRpc::XmlRpcValue GetXmlRpcParamOrThrow (const std::string &name)
 Gets an XML-RPC value from the parameter server. More...
 
std::vector< std::string > GetStringVectorParamOrThrow (const std::string &name)
 Gets a vector of strings from the parameter server. More...
 
std::vector< double > GetDoubleVectorParamOrThrow (const std::string &name)
 Gets a vector of doubles from the parameter server. More...
 
std::vector< float > GetFloatVectorParamOrThrow (const std::string &name)
 Gets a vector of floats from the parameter server. More...
 
std::vector< int > GetIntVectorParamOrThrow (const std::string &name)
 Gets a vector of ints from the parameter server. More...
 
std::vector< bool > GetBoolVectorParamOrThrow (const std::string &name)
 Gets a vector of bools from the parameter server. More...
 
std::map< std::string,
std::string > 
GetStringMapParamOrThrow (const std::string &name)
 Gets a map from strings to string from the parameter server. More...
 
std::map< std::string, double > GetDoubleMapParamOrThrow (const std::string &name)
 Gets a map from strings to doubles from the parameter server. More...
 
std::map< std::string, float > GetFloatMapParamOrThrow (const std::string &name)
 Gets a map from strings to floats from the parameter server. More...
 
std::map< std::string, int > GetIntMapParamOrThrow (const std::string &name)
 Gets a map from strings to ints from the parameter server. More...
 
std::map< std::string, bool > GetBoolMapParamOrThrow (const std::string &name)
 Gets a map from strings to bools from the parameter server. More...
 
void WaitForTime ()
 Wait for simulated time to begin. More...
 
template<typename T >
void get_xyz (const T &value, double *x, double *y, double *z)
 
template<>
void get_xyz (const Eigen::Vector3f &value, double *x, double *y, double *z)
 
template<>
void get_xyz (const Eigen::Vector3d &value, double *x, double *y, double *z)
 
template<>
void get_xyz (const geometry_msgs::Point &value, double *x, double *y, double *z)
 
template<>
void get_xyz (const geometry_msgs::Vector3 &value, double *x, double *y, double *z)
 
template<>
void get_xyz (const pcl::PointXYZ &value, double *x, double *y, double *z)
 
template<>
void get_xyz (const pcl::PointXYZRGB &value, double *x, double *y, double *z)
 
template<>
void get_xyz (const pcl::Normal &value, double *x, double *y, double *z)
 
template<typename T >
Eigen::Vector3d AsVector3d (const T &value)
 Function to get the XYZ value from common ROS types. More...
 
visualization_msgs::MarkerArray AxesMarkerArray (const std::string &ns, const std::string &frame_id, const geometry_msgs::Pose &pose, double scale)
 Generates an x/y/z axis marker given a pose. More...
 
std::vector
< visualization_msgs::InteractiveMarkerControl > 
FixedOrientationSixDofControls ()
 Generates 6 DOF controls with fixed orientations. More...
 
std::vector
< visualization_msgs::InteractiveMarkerControl > 
FreeOrientationSixDofControls ()
 Generates 6 DOF controls with changeable orientations. More...
 
std::vector
< visualization_msgs::InteractiveMarkerControl > 
SixDofControls (uint8_t orientation_mode)
 (Somewhat internal). Generates a 6 DOF controls. More...
 

Typedef Documentation

typedef pcl::PointXYZRGB rapid::PointC

Definition at line 12 of file pcl_typedefs.h.

typedef pcl::PointCloud<pcl::PointXYZRGB> rapid::PointCloudC

Definition at line 14 of file pcl_typedefs.h.

typedef pcl::PointCloud<pcl::PointXYZ> rapid::PointCloudP

Definition at line 13 of file pcl_typedefs.h.

typedef pcl::PointXYZ rapid::PointP

Definition at line 11 of file pcl_typedefs.h.

Function Documentation

bool rapid::AreObbsInCollision ( const geometry_msgs::Pose &  pose1,
const geometry_msgs::Vector3 &  scale1,
const geometry_msgs::Pose &  pose2,
const geometry_msgs::Vector3 &  scale2 
)

Returns true if the given oriented bounding boxes are colliding.

The poses must be in the same frame and the scales must be in the same units.

Parameters
[in]pose1The pose of the first box.
[in]scale1The x/y/z dimensions of the first box.
[in]pose2The pose of the second box.
[in]scale2The x/y/z dimensions of the second box.
Returns
true if the given oriented bounding boxes are colliding, false otherwise.
template<typename T >
Eigen::Vector3d rapid::AsVector3d ( const T &  value)

Function to get the XYZ value from common ROS types.

These include:

  • geometry_msgs: Point and Vector3
  • pcl: PointXYZ, PointXYZRGB, Normal See rapid_utils/vector3.hpp for the full list of types.

You can define your own template specialization of get_xyz for this to work with other types.

Parameters
[in]valueA "vector3"-like object, see description above.
Exceptions
std::invalid_argumentif the type is not supported.
Returns
An Eigen::Vector3d.

Definition at line 79 of file vector3.hpp.

visualization_msgs::MarkerArray rapid::AxesMarkerArray ( const std::string &  ns,
const std::string &  frame_id,
const geometry_msgs::Pose &  pose,
double  scale 
)

Generates an x/y/z axis marker given a pose.

The x-axis is red, y is green, z is blue.

Example usage:

visualization_msgs::MarkerArray axes_markers =
rapid::AxesMarkers("markers", "base_link", pose, 0.1);
Parameters
[in]nsThe namespace for the markers.
[in]frame_idThe frame_id of the pose to visualize.
[in]poseThe pose to visualize.
[in]scaleThe length of each colored cylinder bar. The cylinder diameters are 10% of scale.
Returns
The axes markers.
fcl::OBB rapid::BoxToOBB ( const geometry_msgs::Pose &  pose,
const geometry_msgs::Vector3 &  scale 
)

Returns an fcl::OBB from a Pose and Vector3 message.

Note
The OBB documentation says that the X axis of the rotation matrix "is assumed" to point in the direction of the longest dimension (and Z points towards the shortest). This function does not do so, but collision checking still seems to work.
Returns
The fcl::OBB
std::string rapid::ErrorString ( const moveit::planning_interface::MoveItErrorCode &  error_code)

Returns a string describing the given MoveIt error code.

Parameters
[in]error_codeThe MoveItErrorCode
Returns
A string corresponding to the name of the code in moveit_msgs::MoveItErrorCodes.
std::string rapid::ErrorString ( const moveit_msgs::MoveItErrorCodes &  error_code)

Returns a string describing the given MoveIt error code.

Parameters
[in]error_codeThe MoveItErrorCode
Returns
A string corresponding to the name of the code in moveit_msgs::MoveItErrorCodes.
std::vector<visualization_msgs::InteractiveMarkerControl> rapid::FixedOrientationSixDofControls ( )

Generates 6 DOF controls with fixed orientations.

A fixed orientation means that as the user rotates the interactive marker, the direction of the controls stay fixed at their initial orientations.

Note that the scale of the controls is determined by the scale field of your interactive marker.

Returns
A list of InteractiveMarkerControls. These can be appended to an InteractiveMarker to make it draggable and rotatable.
std::vector<visualization_msgs::InteractiveMarkerControl> rapid::FreeOrientationSixDofControls ( )

Generates 6 DOF controls with changeable orientations.

A "free" orientation means that as the user rotates the interactive marker, the controls move along with the marker.

Note that the scale of the controls is determined by the scale field of your interactive marker.

Returns
A list of InteractiveMarkerControls. These can be appended to an InteractiveMarker to make it draggable and rotatable.
template<typename T >
void rapid::get_xyz ( const T &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 10 of file vector3.hpp.

template<>
void rapid::get_xyz ( const Eigen::Vector3f &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 15 of file vector3.hpp.

template<>
void rapid::get_xyz ( const Eigen::Vector3d &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 22 of file vector3.hpp.

template<>
void rapid::get_xyz ( const geometry_msgs::Point &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 29 of file vector3.hpp.

template<>
void rapid::get_xyz ( const geometry_msgs::Vector3 &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 37 of file vector3.hpp.

template<>
void rapid::get_xyz ( const pcl::PointXYZ &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 45 of file vector3.hpp.

template<>
void rapid::get_xyz ( const pcl::PointXYZRGB &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 52 of file vector3.hpp.

template<>
void rapid::get_xyz ( const pcl::Normal &  value,
double *  x,
double *  y,
double *  z 
)

Definition at line 59 of file vector3.hpp.

std::map<std::string, bool> rapid::GetBoolMapParamOrThrow ( const std::string &  name)

Gets a map from strings to bools from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The map from strings to bools
Exceptions
std::runtime_errorif the parameter does not exist.
bool rapid::GetBoolParamOrThrow ( const std::string &  name)

Gets a bool from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The bool parameter
Exceptions
std::runtime_errorif the parameter does not exist.
std::vector<bool> rapid::GetBoolVectorParamOrThrow ( const std::string &  name)

Gets a vector of bools from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The vector of bools
Exceptions
std::runtime_errorif the parameter does not exist.
std::map<std::string, double> rapid::GetDoubleMapParamOrThrow ( const std::string &  name)

Gets a map from strings to doubles from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The map from strings to doubles
Exceptions
std::runtime_errorif the parameter does not exist.
double rapid::GetDoubleParamOrThrow ( const std::string &  name)

Gets a double from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The double parameter
Exceptions
std::runtime_errorif the parameter does not exist.
std::vector<double> rapid::GetDoubleVectorParamOrThrow ( const std::string &  name)

Gets a vector of doubles from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The vector of doubles
Exceptions
std::runtime_errorif the parameter does not exist.
std::map<std::string, float> rapid::GetFloatMapParamOrThrow ( const std::string &  name)

Gets a map from strings to floats from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The map from strings to floats
Exceptions
std::runtime_errorif the parameter does not exist.
float rapid::GetFloatParamOrThrow ( const std::string &  name)

Gets a float from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The float parameter
Exceptions
std::runtime_errorif the parameter does not exist.
std::vector<float> rapid::GetFloatVectorParamOrThrow ( const std::string &  name)

Gets a vector of floats from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The vector of floats
Exceptions
std::runtime_errorif the parameter does not exist.
std::map<std::string, int> rapid::GetIntMapParamOrThrow ( const std::string &  name)

Gets a map from strings to ints from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The map from strings to ints
Exceptions
std::runtime_errorif the parameter does not exist.
int rapid::GetIntParamOrThrow ( const std::string &  name)

Gets an int from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The int parameter
Exceptions
std::runtime_errorif the parameter does not exist.
std::vector<int> rapid::GetIntVectorParamOrThrow ( const std::string &  name)

Gets a vector of ints from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The vector of ints
Exceptions
std::runtime_errorif the parameter does not exist.
std::map<std::string, std::string> rapid::GetStringMapParamOrThrow ( const std::string &  name)

Gets a map from strings to string from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The map from strings to strings
Exceptions
std::runtime_errorif the parameter does not exist.
std::string rapid::GetStringParamOrThrow ( const std::string &  name)

Gets a string from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The string parameter
Exceptions
std::runtime_errorif the parameter does not exist.
std::vector<std::string> rapid::GetStringVectorParamOrThrow ( const std::string &  name)

Gets a vector of strings from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The vector of strings
Exceptions
std::runtime_errorif the parameter does not exist.
XmlRpc::XmlRpcValue rapid::GetXmlRpcParamOrThrow ( const std::string &  name)

Gets an XML-RPC value from the parameter server.

Parameters
[in]nameThe name of the parameter in the current node's namespace.
Returns
The XML-RPC value
Exceptions
std::runtime_errorif the parameter does not exist.
bool rapid::IsSuccess ( const moveit::planning_interface::MoveItErrorCode &  error_code)

Returns true if the error code corresponds to success.

You can already use a MoveItErrorCode as a bool, but it can lead to unintuitive code (true is success).

MoveItErrorCode error = group.plan(...);
if (error) {
// This actually corresponds to success!
}

Instead:

MoveItErrorCode error = group.plan(...);
if (rapid::IsSuccess(error)) {
// More intuitive
}
Parameters
[in]error_codeThe MoveItErrorCode
Returns
True if the error code is success, false otherwise.
bool rapid::IsSuccess ( const moveit_msgs::MoveItErrorCodes &  error_code)

Returns true if the error code corresponds to success.

Parameters
[in]error_codeThe MoveItErrorCode
Returns
True if the error code is success, false otherwise.
std::vector<visualization_msgs::InteractiveMarkerControl> rapid::SixDofControls ( uint8_t  orientation_mode)

(Somewhat internal). Generates a 6 DOF controls.

For clarity, use either FixedOrientationSixDofControls() or FreeOrientationSixDofControls().

Note that the scale of the controls is determined by the scale field of your interactive marker.

Returns
A list of InteractiveMarkerControls. These can be appended to an InteractiveMarker to make it draggable and rotatable.
void rapid::WaitForTime ( )

Wait for simulated time to begin.

Blocks until the current time is non-zero.