Public Member Functions | Private Member Functions | Private Attributes
ManipulationTransformsROS Class Reference

#include <manipulation_transforms_ros.h>

List of all members.

Public Member Functions

void init_services (const std::string &ns="")
bool loadInitialTransforms (manipulation_transforms::LoadInitialTransforms::Request &req, manipulation_transforms::LoadInitialTransforms::Response &resp)
 Provides the service interface for reloading grasp transforms from param server.
 ManipulationTransformsROS (const std::string &reference_frame="")
 ManipulationTransformsROS (const std::string &reference_frame, const std::string &ns)
 ManipulationTransformsROS (const std::string &reference_frame, geometry_msgs::PoseStamped &obj_init_pose, std::vector< geometry_msgs::PoseStamped > effector_init_poses)
bool mapEffectorPosesToObject (manipulation_transforms::MapEffectorPosesToObject::Request &req, manipulation_transforms::MapEffectorPosesToObject::Response &resp)
 Provides the service interface to mapEffectorPosesToObject.
bool mapEffectorTrajectoriesToObject (manipulation_transforms::MapEffectorTrajectoriesToObject::Request &req, manipulation_transforms::MapEffectorTrajectoriesToObject::Response &resp)
 Provides the service interface for getting a full object trajectory from effector trajectories.
bool mapEffectorTwistsToObject (manipulation_transforms::MapEffectorTwistsToObject::Request &req, manipulation_transforms::MapEffectorTwistsToObject::Response &resp)
 Provides the service interface to mapEffectorTwistsToObject.
bool mapObjectPoseToEffectors (manipulation_transforms::MapObjectPoseToEffectors::Request &req, manipulation_transforms::MapObjectPoseToEffectors::Response &resp)
 Provides the service interface to mapObjectPoseToEffectors.
bool mapObjectTrajectoryToEffectors (manipulation_transforms::MapObjectTrajectoryToEffectors::Request &req, manipulation_transforms::MapObjectTrajectoryToEffectors::Response &resp)
 Provides the service interface for getting full effector trajectories from an object trajectory.
bool mapObjectTwistToEffectors (manipulation_transforms::MapObjectTwistToEffectors::Request &req, manipulation_transforms::MapObjectTwistToEffectors::Response &resp)
 Provides the service interface to mapObjectTwistToEffectors.
bool setInitialTransforms (manipulation_transforms::SetInitialTransforms::Request &req, manipulation_transforms::SetInitialTransforms::Response &resp)
 Provides the service interface for setting grasp transforms as a service call.
virtual ~ManipulationTransformsROS ()

Private Member Functions

int checkForParamServerTransforms (const ros::NodeHandle &nh, bool warn=false)
 Checks for availability of grasp transforms on the parameter server using local param nodehandle.
bool loadParamServerTransforms (const ros::NodeHandle &nh)
 Load rigid grasp transforms from parameter server.

Private Attributes

std::string BASE_FRAME_
std::vector< btTransformeffector_init_poses
ros::ServiceServer effector_poses_to_object_service_
 Services for querying object and effector poses.
ros::ServiceServer effector_trajectories_to_object_service_
ros::ServiceServer effector_twists_to_object_service_
ros::ServiceServer load_initial_transforms_service_
int n_effectors_
btTransform obj_initial_pose_
ros::ServiceServer object_pose_to_effectors_service_
ros::ServiceServer object_trajectory_to_effectors_service_
ros::ServiceServer object_twist_to_effectors_service_
ros::NodeHandle param_nh_
ros::NodeHandle private_nh_
ros::ServiceServer set_initial_transforms_service_
ManipulationTransforms solver_

Detailed Description

Definition at line 63 of file manipulation_transforms_ros.h.


Constructor & Destructor Documentation

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 
)
Parameters:
nameNamespace 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 
)
Parameters:
obj_init_poseTransform from initial pose of object to reference frame
effector_init_posesTransforms from initial pose of each effector to reference frame

Definition at line 79 of file manipulation_transforms_ros.cpp.

Definition at line 112 of file manipulation_transforms_ros.cpp.


Member Function Documentation

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.

Parameters:
nhNodehandle to query for params
warnWarn the user if params are not found
Returns:
The number of effector transforms found on the parameter, with names matching "effector#_init_pose/position" and "effector#_init_pose/orientation". Returns -1 if no transform is found for the object matching "obj_init_pose/position" and "obj_init_pose/orientation"

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.

Provides the service interface for reloading grasp transforms from param server.

Definition at line 172 of file manipulation_transforms_ros.cpp.

Load rigid grasp transforms from parameter server.

Parameters:
nhNodehandle to query for params
n_effectorsThe number of effectors to look for
warnWarn the user if params are not found

Definition at line 377 of file manipulation_transforms_ros.cpp.

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.

Provides the service interface to mapEffectorTwistsToObject.

Definition at line 262 of file manipulation_transforms_ros.cpp.

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.

Provides the service interface to mapObjectTwistToEffectors.

Definition at line 298 of file manipulation_transforms_ros.cpp.

Provides the service interface for setting grasp transforms as a service call.

Definition at line 133 of file manipulation_transforms_ros.cpp.


Member Data Documentation

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.

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.


The documentation for this class was generated from the following files:


manipulation_transforms
Author(s): Jonathan Scholz
autogenerated on Tue Jan 7 2014 11:10:08