ShadowHandUtilityLibrary
Namespaces | Enumerations | Functions
shadow_utils.hpp File Reference
#include <shadowlibs/shadow_imports.hpp>
Include dependency graph for shadow_utils.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 shadow_utils
 Contains various utility functions for RViz visualization, conversions, transformations and robot controllers.
 

Enumerations

enum  shadow_utils::SHAPE_PRIMITIVES { shadow_utils::SHAPE_PRIMITIVES::BOX, shadow_utils::SHAPE_PRIMITIVES::CYLINDER, shadow_utils::SHAPE_PRIMITIVES::CONE, shadow_utils::SHAPE_PRIMITIVES::SPHERE }
 Primitive shapes used for RViz objects. More...
 

Functions

std::ostream & operator<< (std::ostream &out, const geometry_msgs::Pose &pose)
 Print ROS Pose messages. More...
 
template<typename T >
std::ostream & operator<< (std::ostream &out, const std::vector< T > &joint_data)
 Print vector data. More...
 
Eigen::Quaternionf shadow_utils::ypr2quat (float y, float p, float r)
 Conversion from YPR to Quaternion. More...
 
void shadow_utils::quat2ypr (tf::Quaternion &q, double &r, double &p, double &y)
 Conversion from Quaternion to YPR. More...
 
template<typename F >
shadow_utils::deg2rad (F deg)
 Conversion from degree to radians. More...
 
template<typename F >
shadow_utils::rad2deg (F rad)
 Conversion from radians to degrees. More...
 
void shadow_utils::createCollisionObjectFromPrimitive (moveit_msgs::CollisionObject &collision_obj, std::string primitive_id, shape_msgs::SolidPrimitive &primitive, geometry_msgs::Pose &obj_pose, shadow_utils::SHAPE_PRIMITIVES primitive_type, const std::vector< double > &primitive_dims)
 Create collision object for the planning scene, used by MoveIt planning. More...
 
void shadow_utils::createAttachedObjectFromPrimitive (moveit_msgs::AttachedCollisionObject &attached_obj, std::string primitive_id, shape_msgs::SolidPrimitive &primitive, geometry_msgs::Pose &obj_pose, shadow_utils::SHAPE_PRIMITIVES primitive_type, const std::vector< double > &primitive_dims)
 Create attached object for the planning scene, used by MoveIt planning when attaching object to robot This helps plan when an object is "attached" to the end of a robot, after grasping. More...
 
void shadow_utils::addCollisionObjectToScene (moveit_msgs::CollisionObject &collision_obj, moveit_msgs::PlanningScene &planning_scene_msg, ros::Publisher &planning_scene_diff_publisher)
 Add a collision object to the planning scene. More...
 
void shadow_utils::addAttachedObjectToScene (moveit_msgs::AttachedCollisionObject &attached_obj, moveit_msgs::PlanningScene &planning_scene_msg, ros::Publisher &planning_scene_diff_publisher)
 Add a collision object to the planning scene. More...
 
void shadow_utils::moveCollisionObjectInScene (moveit_msgs::CollisionObject &collision_obj, geometry_msgs::Pose &obj_pose, moveit_msgs::PlanningScene &planning_scene_msg, ros::Publisher &planning_scene_diff_publisher)
 Move an existing collision object in the planning scene. More...
 
void shadow_utils::attachObjectToRobot (moveit_msgs::AttachedCollisionObject &attached_obj, moveit_msgs::PlanningScene &planning_scene_msg, ros::Publisher &planning_scene_diff_publisher)
 Attach a collision object to the robot. More...
 
void shadow_utils::detachObjectFromRobot (moveit_msgs::AttachedCollisionObject &attached_obj, moveit_msgs::PlanningScene &planning_scene_msg, ros::Publisher &planning_scene_diff_publisher)
 Detach an attached collision object from the robot. More...
 
void shadow_utils::removeAllObjectsFromScene (moveit::planning_interface::PlanningSceneInterface &planning_scene_interface)
 Remove all objects from the scene. More...
 
void shadow_utils::removeCollisionObjectFromScene (moveit::planning_interface::PlanningSceneInterface &planning_scene_interface, std::string obj_id)
 Remove some object from the scene. More...
 
void shadow_utils::getPoseFromPositionYPR (geometry_msgs::Pose &pose, float x, float y, float z, float yaw, float pitch, float roll)
 Generate ROS Pose from position and YPR. More...
 
void shadow_utils::getPoseFromPositionQuaternion (geometry_msgs::Pose &pose, float x, float y, float z, float qx, float qy, float qz, float qw)
 Generate ROS Pose from position and quaternion. More...
 
void shadow_utils::getPoseFromPositionYPR (geometry_msgs::Pose &pose, float x, float y, float z, tf::Vector3 &v)
 
void shadow_utils::getPoseFromPositionQuaternion (geometry_msgs::Pose &pose, float x, float y, float z, tf::Quaternion &q)
 
void shadow_utils::getPoseFromPositionQuaternion (geometry_msgs::Pose &pose, tf::StampedTransform &tf, tf::Quaternion &q)
 
void shadow_utils::getTfFromFrames (tf::TransformListener &listener, tf::StampedTransform &tf, std::string parent_frame, std::string child_frame)
 Get TF from parent and child frames. More...
 
std::string shadow_utils::getControllerTopic (std::string &joint_name)
 Get the name of the controller responsible for controlling the given joint name. More...
 
std::vector< ros::Publisher > shadow_utils::createJointControllerPublishers (std::vector< std::string > &joint_names, ros::NodeHandle &n)
 Create a vector of publishers for each given joint name, using the ROS node handle. More...
 
void shadow_utils::broadcastTransformForGrasp (std::vector< double > xyzrpy, const std::string frame_name)
 Broadcasts a transform from the wrist to given frame, which can be used for planning targets for finger. More...
 
geometry_msgs::Pose shadow_utils::getPoseBetweenFrames (const std::string parent_frame, const std::string child_frame)
 Get the pose between two frames. More...
 
moveit_msgs::RobotState shadow_utils::computeJointsFromPose (moveit::planning_interface::MoveGroupInterface &move_group_interface, double timeout, int num_attempts, geometry_msgs::Pose &target_pose)
 Creates a RobotState using the inverse kinematics solver, given a target pose. Uses a service call to the "compute_ik" service to obtain the joint angles needed for the given MoveGroup to reach the specified target pose. More...
 
void shadow_utils::startTrajectoryController (ros::NodeHandle n, std::string controller_name)
 Starts trajectory controller for arm or hand, using ControllerManager service call. More...
 
void shadow_utils::stopTrajectoryController (ros::NodeHandle n, std::string controller_name)
 Stops trajectory controller for arm or hand, using ControllerManager service call. More...
 

Function Documentation

std::ostream& operator<< ( std::ostream &  out,
const geometry_msgs::Pose &  pose 
)

Print ROS Pose messages.

Parameters
outOutput stream
poseThe pose to print
Returns
Output stream, so that we can chain further calls to operator<<
template<typename T >
std::ostream& operator<< ( std::ostream &  out,
const std::vector< T > &  joint_data 
)

Print vector data.

Template Parameters
TTemplated over whatever data type std::vector accepts
Parameters
outOutput stream
joint_dataThe data vector to print
Returns
Output stream, so that we can chain further calls to operator<<