#include <manipulation_transforms_ros.h>
Definition at line 63 of file manipulation_transforms_ros.h.
| ManipulationTransformsROS::ManipulationTransformsROS | ( | const std::string & | reference_frame = "" | ) | 
Default constructor for ManipulationTransformsROS If initialized with this constructor, initial grasp transforms must be provided manually through a service call to setInitialTransforms
Definition at line 53 of file manipulation_transforms_ros.cpp.
| ManipulationTransformsROS::ManipulationTransformsROS | ( | const std::string & | reference_frame, | 
| const std::string & | ns | ||
| ) | 
| name | Namespace to prepend to the parameter nodehandle | 
Definition at line 59 of file manipulation_transforms_ros.cpp.
| ManipulationTransformsROS::ManipulationTransformsROS | ( | const std::string & | reference_frame, | 
| geometry_msgs::PoseStamped & | obj_init_pose, | ||
| std::vector< geometry_msgs::PoseStamped > | effector_init_poses | ||
| ) | 
| obj_init_pose | Transform from initial pose of object to reference frame | 
| effector_init_poses | Transforms from initial pose of each effector to reference frame | 
Definition at line 79 of file manipulation_transforms_ros.cpp.
| ManipulationTransformsROS::~ManipulationTransformsROS | ( | ) |  [virtual] | 
Definition at line 112 of file manipulation_transforms_ros.cpp.
| int ManipulationTransformsROS::checkForParamServerTransforms | ( | const ros::NodeHandle & | nh, | 
| bool | warn = false | ||
| ) |  [private] | 
Checks for availability of grasp transforms on the parameter server using local param nodehandle.
| nh | Nodehandle to query for params | 
| warn | Warn the user if params are not found | 
Definition at line 352 of file manipulation_transforms_ros.cpp.
| void ManipulationTransformsROS::init_services | ( | const std::string & | ns = "" | ) | 
Definition at line 114 of file manipulation_transforms_ros.cpp.
| bool ManipulationTransformsROS::loadInitialTransforms | ( | manipulation_transforms::LoadInitialTransforms::Request & | req, | 
| manipulation_transforms::LoadInitialTransforms::Response & | resp | ||
| ) | 
Provides the service interface for reloading grasp transforms from param server.
Definition at line 172 of file manipulation_transforms_ros.cpp.
| bool ManipulationTransformsROS::loadParamServerTransforms | ( | const ros::NodeHandle & | nh | ) |  [private] | 
Load rigid grasp transforms from parameter server.
| nh | Nodehandle to query for params | 
| n_effectors | The number of effectors to look for | 
| warn | Warn the user if params are not found | 
Definition at line 377 of file manipulation_transforms_ros.cpp.
| bool ManipulationTransformsROS::mapEffectorPosesToObject | ( | manipulation_transforms::MapEffectorPosesToObject::Request & | req, | 
| manipulation_transforms::MapEffectorPosesToObject::Response & | resp | ||
| ) | 
Provides the service interface to mapEffectorPosesToObject.
Definition at line 190 of file manipulation_transforms_ros.cpp.
Provides the service interface for getting a full object trajectory from effector trajectories.
Provides the service interface for getting an object trajectory from effector trajectories.
The service response will include solutions for the object for any of the fields provided in the sequence of trajectory points
Definition at line 345 of file manipulation_transforms_ros.cpp.
| bool ManipulationTransformsROS::mapEffectorTwistsToObject | ( | manipulation_transforms::MapEffectorTwistsToObject::Request & | req, | 
| manipulation_transforms::MapEffectorTwistsToObject::Response & | resp | ||
| ) | 
Provides the service interface to mapEffectorTwistsToObject.
Definition at line 262 of file manipulation_transforms_ros.cpp.
| bool ManipulationTransformsROS::mapObjectPoseToEffectors | ( | manipulation_transforms::MapObjectPoseToEffectors::Request & | req, | 
| manipulation_transforms::MapObjectPoseToEffectors::Response & | resp | ||
| ) | 
Provides the service interface to mapObjectPoseToEffectors.
Definition at line 226 of file manipulation_transforms_ros.cpp.
Provides the service interface for getting full effector trajectories from an object trajectory.
Provides the service interface for getting effector trajectories from an object trajectory.
The service response will include solutions for all effectors for any of the fields provided in the sequence of trajectory points
Definition at line 335 of file manipulation_transforms_ros.cpp.
| bool ManipulationTransformsROS::mapObjectTwistToEffectors | ( | manipulation_transforms::MapObjectTwistToEffectors::Request & | req, | 
| manipulation_transforms::MapObjectTwistToEffectors::Response & | resp | ||
| ) | 
Provides the service interface to mapObjectTwistToEffectors.
Definition at line 298 of file manipulation_transforms_ros.cpp.
| bool ManipulationTransformsROS::setInitialTransforms | ( | manipulation_transforms::SetInitialTransforms::Request & | req, | 
| manipulation_transforms::SetInitialTransforms::Response & | resp | ||
| ) | 
Provides the service interface for setting grasp transforms as a service call.
Definition at line 133 of file manipulation_transforms_ros.cpp.
| std::string ManipulationTransformsROS::BASE_FRAME_  [private] | 
The frame in which all initialization transforms are defined
Definition at line 156 of file manipulation_transforms_ros.h.
initial effector poses in BASE_FRAME
Definition at line 160 of file manipulation_transforms_ros.h.
Services for querying object and effector poses.
Definition at line 147 of file manipulation_transforms_ros.h.
Definition at line 151 of file manipulation_transforms_ros.h.
Definition at line 149 of file manipulation_transforms_ros.h.
Definition at line 153 of file manipulation_transforms_ros.h.
| int ManipulationTransformsROS::n_effectors_  [private] | 
Definition at line 157 of file manipulation_transforms_ros.h.
obj pose in base_footprint frame
Definition at line 159 of file manipulation_transforms_ros.h.
Definition at line 148 of file manipulation_transforms_ros.h.
Definition at line 152 of file manipulation_transforms_ros.h.
Definition at line 150 of file manipulation_transforms_ros.h.
for reading parameters
Definition at line 142 of file manipulation_transforms_ros.h.
for service advertisers
Definition at line 143 of file manipulation_transforms_ros.h.
Definition at line 154 of file manipulation_transforms_ros.h.
The solver object for computing new relative poses
Definition at line 144 of file manipulation_transforms_ros.h.