Public Member Functions | Public Attributes
moveit_simple_grasps::GraspData Class Reference

#include <grasp_data.h>

List of all members.

Public Member Functions

 GraspData ()
 Constructor.
bool loadRobotGraspData (const ros::NodeHandle &nh, const std::string &end_effector)
 Loads grasp data from a yaml file (load from roslaunch)
void print ()
 Debug data to console.
bool setRobotState (robot_state::RobotStatePtr &robot_state, const trajectory_msgs::JointTrajectory &posture)
 Alter a robot state so that the end effector corresponding to this grasp data is in a grasp posture.
bool setRobotStateGrasp (robot_state::RobotStatePtr &robot_state)
 Alter a robot state so that the end effector corresponding to this grasp data is in grasp state (CLOSED)
bool setRobotStatePreGrasp (robot_state::RobotStatePtr &robot_state)
 Alter a robot state so that the end effector corresponding to this grasp data is in pre-grasp state (OPEN)

Public Attributes

int angle_resolution_
double approach_retreat_desired_dist_
double approach_retreat_min_dist_
std::string base_link_
std::string ee_group_
std::string ee_parent_link_
double grasp_depth_
geometry_msgs::Pose grasp_pose_to_eef_pose_
trajectory_msgs::JointTrajectory grasp_posture_
double object_size_
trajectory_msgs::JointTrajectory pre_grasp_posture_

Detailed Description

Definition at line 54 of file grasp_data.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 53 of file grasp_data.cpp.


Member Function Documentation

bool moveit_simple_grasps::GraspData::loadRobotGraspData ( const ros::NodeHandle nh,
const std::string &  end_effector 
)

Loads grasp data from a yaml file (load from roslaunch)

Parameters:
nodehandle - allows for namespacing
endeffector name - which side of a two handed robot to load data for. should correspond to SRDF EE names
Returns:
true on success

Definition at line 63 of file grasp_data.cpp.

Debug data to console.

Definition at line 287 of file grasp_data.cpp.

bool moveit_simple_grasps::GraspData::setRobotState ( robot_state::RobotStatePtr &  robot_state,
const trajectory_msgs::JointTrajectory &  posture 
)

Alter a robot state so that the end effector corresponding to this grasp data is in a grasp posture.

Parameters:
jointstate of robot
posture- what state to set the end effector
Returns:
true on success

Definition at line 272 of file grasp_data.cpp.

bool moveit_simple_grasps::GraspData::setRobotStateGrasp ( robot_state::RobotStatePtr &  robot_state)

Alter a robot state so that the end effector corresponding to this grasp data is in grasp state (CLOSED)

Parameters:
jointstate of robot
Returns:
true on success

Definition at line 267 of file grasp_data.cpp.

bool moveit_simple_grasps::GraspData::setRobotStatePreGrasp ( robot_state::RobotStatePtr &  robot_state)

Alter a robot state so that the end effector corresponding to this grasp data is in pre-grasp state (OPEN)

Parameters:
jointstate of robot
Returns:
true on success

Definition at line 263 of file grasp_data.cpp.


Member Data Documentation

Definition at line 64 of file grasp_data.h.

Definition at line 65 of file grasp_data.h.

Definition at line 66 of file grasp_data.h.

Definition at line 60 of file grasp_data.h.

Definition at line 62 of file grasp_data.h.

Definition at line 61 of file grasp_data.h.

Definition at line 63 of file grasp_data.h.

Definition at line 57 of file grasp_data.h.

trajectory_msgs::JointTrajectory moveit_simple_grasps::GraspData::grasp_posture_

Definition at line 59 of file grasp_data.h.

Definition at line 67 of file grasp_data.h.

trajectory_msgs::JointTrajectory moveit_simple_grasps::GraspData::pre_grasp_posture_

Definition at line 58 of file grasp_data.h.


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


moveit_simple_grasps
Author(s): Dave Coleman
autogenerated on Thu Jun 6 2019 20:55:20