simple_robot_control::Arm Class Reference

#include <arm_control.h>

List of all members.

Public Types

enum  approach_direction_t {
  FRONTAL, FROM_BELOW, FROM_ABOVE, FROM_RIGHT_SIDEWAYS,
  FROM_RIGHT_UPRIGHT, FROM_LEFT_UPRIGHT, FROM_LEFT_SIDEWAYS
}

Public Member Functions

 Arm (char arm_side, bool collision_checking=true)
vector< double > getCurrentJointAngles ()
bool getIK (const geometry_msgs::PoseStamped &pose, vector< double > &joint_angles, vector< double > *ik_seed_pos=NULL)
bool goToJointPos (const double *positions, int num_positions, double max_time=3.0, bool wait=true)
bool goToJointPos (const vector< double > &positions, double max_time=3.0, bool wait=true)
bool goToJointPosWithCollisionChecking (const vector< double > &positions, double max_time=3.0, bool wait=true)
bool isAtPos (const std::vector< double > &pos_vec)
bool moveGrippertoPose (const tf::StampedTransform &pose, double max_time=5.0, bool wait=true, vector< double > *ik_seed_pos=0)
bool moveGrippertoPoseWithCollisionChecking (const tf::StampedTransform &pose, double max_time=5.0, bool wait=true, std::string planner="ompl")
bool moveGrippertoPoseWithOrientationConstraints (const tf::StampedTransform &tf, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time=5.0, bool wait=true, double tolerance=0.2)
bool moveGripperToPosition (const tf::Vector3 &position, string frame_id, approach_direction_t approach=FRONTAL, double max_time=5.0, bool wait=true, vector< double > *ik_seed_pos=0)
bool moveGrippertoPositionWithCollisionChecking (const tf::Vector3 &position, string frame_id, approach_direction_t approach=FRONTAL, double max_time=5.0, bool wait=true, std::string planner="ompl")
bool moveWristRollLinktoPose (const geometry_msgs::PoseStamped &pose, double max_time=5.0, bool wait=true, vector< double > *ik_seed_pos=0)
bool moveWristRollLinktoPose (const tf::StampedTransform &pose, double max_time=5.0, bool wait=true, vector< double > *ik_seed_pos=0)
bool moveWristRollLinktoPoseWithCollisionChecking (const tf::StampedTransform &pose, double max_time=5.0, bool wait=true, std::string planner="ompl")
bool moveWristRollLinktoPoseWithCollisionChecking (const geometry_msgs::PoseStamped &pose, double max_time=5.0, bool wait=true, std::string planner="ompl")
bool moveWristRollLinktoPoseWithOrientationConstraints (const geometry_msgs::PoseStamped &pose, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time=5.0, bool wait=true, double tolerance=0.2)
bool moveWristRollLinktoPoseWithOrientationConstraints (const tf::StampedTransform &pose, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time=5.0, bool wait=true, double tolerance=0.2)
bool rotateWrist (double radians, double wrist_speed=wrist_speed_, bool wait=true)
bool stretch ()
bool tuck ()
bool updateJointStatePos ()
 ~Arm ()
 Clean up the action client.

Private Member Functions

tf::StampedTransform gripperToWrist (const tf::StampedTransform &pose)
tf::StampedTransform makePose (const tf::Vector3 &position, string frame_id, approach_direction_t approach)
tf::StampedTransform wristToGripper (const tf::StampedTransform &pose)

Private Attributes

string armside_str
vector< double > current_joint_angles_
string group_name
ros::ServiceClient ik_service_client_
vector< string > joint_names
actionlib::SimpleActionClient
< move_arm_msgs::MoveArmAction > * 
move_arm_client_
ros::NodeHandle nh_
actionlib::SimpleActionClient
< pr2_controllers_msgs::JointTrajectoryAction > 
traj_client_

Static Private Attributes

static const double gripperlength = 0.18
static const double wrist_speed_ = 2.0

Detailed Description

Definition at line 64 of file arm_control.h.


Member Enumeration Documentation

Enumerator:
FRONTAL 
FROM_BELOW 
FROM_ABOVE 
FROM_RIGHT_SIDEWAYS 
FROM_RIGHT_UPRIGHT 
FROM_LEFT_UPRIGHT 
FROM_LEFT_SIDEWAYS 

Definition at line 133 of file arm_control.h.


Constructor & Destructor Documentation

simple_robot_control::Arm::Arm ( char  arm_side,
bool  collision_checking = true 
)

Constructor: arm_side should be either 'r' or 'l'; collision checking enables ompl planner

Definition at line 17 of file arm_control.cpp.

simple_robot_control::Arm::~Arm (  ) 

Clean up the action client.

Definition at line 76 of file arm_control.cpp.


Member Function Documentation

vector< double > simple_robot_control::Arm::getCurrentJointAngles (  ) 

get joint angles

Definition at line 211 of file arm_control.cpp.

bool simple_robot_control::Arm::getIK ( const geometry_msgs::PoseStamped &  pose,
vector< double > &  joint_angles,
vector< double > *  ik_seed_pos = NULL 
)

get IK from kinematics server

Definition at line 216 of file arm_control.cpp.

bool simple_robot_control::Arm::goToJointPos ( const double *  positions,
int  num_positions,
double  max_time = 3.0,
bool  wait = true 
)

moves arm to joint position. positions should contain a multiple of the 7 arm joint positions to create a trajectory

Definition at line 260 of file arm_control.cpp.

bool simple_robot_control::Arm::goToJointPos ( const vector< double > &  positions,
double  max_time = 3.0,
bool  wait = true 
)

moves arm to joint angle position. positions should contain a multiple of the 7 arm joint positions to create a trajectory

Definition at line 265 of file arm_control.cpp.

bool simple_robot_control::Arm::goToJointPosWithCollisionChecking ( const vector< double > &  positions,
double  max_time = 3.0,
bool  wait = true 
)

uses ompl path planner and moves arm to joint position. positions should contain a multiple of the 7 arm joint positions to create a trajectory.

Definition at line 102 of file arm_control.cpp.

tf::StampedTransform simple_robot_control::Arm::gripperToWrist ( const tf::StampedTransform &  pose  )  [private]

Definition at line 386 of file arm_control.cpp.

bool simple_robot_control::Arm::isAtPos ( const std::vector< double > &  pos_vec  ) 

Checks weather current arm position are the same as in pos_vec (wit some epsilon).

Definition at line 335 of file arm_control.cpp.

tf::StampedTransform simple_robot_control::Arm::makePose ( const tf::Vector3 &  position,
string  frame_id,
approach_direction_t  approach 
) [private]

Definition at line 401 of file arm_control.cpp.

bool simple_robot_control::Arm::moveGrippertoPose ( const tf::StampedTransform &  pose,
double  max_time = 5.0,
bool  wait = true,
vector< double > *  ik_seed_pos = 0 
)

gets IK and moves gripper_tool_frame to pose specified in pose. The orientation can be overridden by above enums.

Definition at line 444 of file arm_control.cpp.

bool simple_robot_control::Arm::moveGrippertoPoseWithCollisionChecking ( const tf::StampedTransform &  pose,
double  max_time = 5.0,
bool  wait = true,
std::string  planner = "ompl" 
)

uses ompl path planner and moves gripper_tool_frame to pose specified in pose. The orientation can be overridden by above enums.

Definition at line 452 of file arm_control.cpp.

bool simple_robot_control::Arm::moveGrippertoPoseWithOrientationConstraints ( const tf::StampedTransform &  tf,
bool  keep_roll,
bool  keep_pitch,
bool  keep_yaw,
double  max_time = 5.0,
bool  wait = true,
double  tolerance = 0.2 
)

uses ompl planner to calculate path and moves wrist roll link to pose specified and keeps the set orientations on the motion path within the tolerance (angle in radians)

Definition at line 468 of file arm_control.cpp.

bool simple_robot_control::Arm::moveGripperToPosition ( const tf::Vector3 &  position,
string  frame_id,
approach_direction_t  approach = FRONTAL,
double  max_time = 5.0,
bool  wait = true,
vector< double > *  ik_seed_pos = 0 
)

gets IK and moves gripper_tool_frame to pose specified in postion and the orientation of the approach direction relative to base coordinate frame

Definition at line 435 of file arm_control.cpp.

bool simple_robot_control::Arm::moveGrippertoPositionWithCollisionChecking ( const tf::Vector3 &  position,
string  frame_id,
approach_direction_t  approach = FRONTAL,
double  max_time = 5.0,
bool  wait = true,
std::string  planner = "ompl" 
)

gets IK and moves gripper_tool_frame to pose specified in postion and the orientation of the approach direction relative to base coordinate frame

Definition at line 460 of file arm_control.cpp.

bool simple_robot_control::Arm::moveWristRollLinktoPose ( const geometry_msgs::PoseStamped &  pose,
double  max_time = 5.0,
bool  wait = true,
vector< double > *  ik_seed_pos = 0 
)

gets IK and moves wrist roll link to pose specified in pose

Definition at line 248 of file arm_control.cpp.

bool simple_robot_control::Arm::moveWristRollLinktoPose ( const tf::StampedTransform &  pose,
double  max_time = 5.0,
bool  wait = true,
vector< double > *  ik_seed_pos = 0 
)

gets IK and moves wrist roll link to pose specified in tf

Definition at line 84 of file arm_control.cpp.

bool simple_robot_control::Arm::moveWristRollLinktoPoseWithCollisionChecking ( const tf::StampedTransform &  pose,
double  max_time = 5.0,
bool  wait = true,
std::string  planner = "ompl" 
)

uses ompl planner to calculate path and moves wrist roll link to pose specified

Definition at line 93 of file arm_control.cpp.

bool simple_robot_control::Arm::moveWristRollLinktoPoseWithCollisionChecking ( const geometry_msgs::PoseStamped &  pose,
double  max_time = 5.0,
bool  wait = true,
std::string  planner = "ompl" 
)

uses ompl planner to calculate path and moves wrist roll link to pose specified in pose

Definition at line 152 of file arm_control.cpp.

bool simple_robot_control::Arm::moveWristRollLinktoPoseWithOrientationConstraints ( const geometry_msgs::PoseStamped &  pose,
bool  keep_roll,
bool  keep_pitch,
bool  keep_yaw,
double  max_time = 5.0,
bool  wait = true,
double  tolerance = 0.2 
)

uses ompl planner to calculate path and moves wrist roll link to pose specified and keeps the set orientations on the motion path within the tolerance (angle in radians)

Definition at line 485 of file arm_control.cpp.

bool simple_robot_control::Arm::moveWristRollLinktoPoseWithOrientationConstraints ( const tf::StampedTransform &  pose,
bool  keep_roll,
bool  keep_pitch,
bool  keep_yaw,
double  max_time = 5.0,
bool  wait = true,
double  tolerance = 0.2 
)

uses ompl planner to calculate path and moves wrist roll link to pose specified and keeps the set orientations on the motion path within the tolerance (angle in radians)

Definition at line 476 of file arm_control.cpp.

bool simple_robot_control::Arm::rotateWrist ( double  radians,
double  wrist_speed = wrist_speed_,
bool  wait = true 
)

Rotates wrist by angle in radians. speed is the amount of time that it would take for one revolution.

Definition at line 324 of file arm_control.cpp.

bool simple_robot_control::Arm::stretch (  ) 

Move arm into stretched out position.

Definition at line 366 of file arm_control.cpp.

bool simple_robot_control::Arm::tuck (  ) 

Move arm into tuck position.

Definition at line 347 of file arm_control.cpp.

bool simple_robot_control::Arm::updateJointStatePos (  ) 

sets current_joint_pos_ to current positions of the robot arm

Definition at line 307 of file arm_control.cpp.

tf::StampedTransform simple_robot_control::Arm::wristToGripper ( const tf::StampedTransform &  pose  )  [private]

Definition at line 393 of file arm_control.cpp.


Member Data Documentation

Definition at line 72 of file arm_control.h.

Definition at line 81 of file arm_control.h.

const double simple_robot_control::Arm::gripperlength = 0.18 [static, private]

Definition at line 67 of file arm_control.h.

Definition at line 73 of file arm_control.h.

ros::ServiceClient simple_robot_control::Arm::ik_service_client_ [private]

Definition at line 77 of file arm_control.h.

vector<string> simple_robot_control::Arm::joint_names [private]

Definition at line 71 of file arm_control.h.

actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction>* simple_robot_control::Arm::move_arm_client_ [private]

Definition at line 74 of file arm_control.h.

ros::NodeHandle simple_robot_control::Arm::nh_ [private]

Definition at line 78 of file arm_control.h.

actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > simple_robot_control::Arm::traj_client_ [private]

Definition at line 75 of file arm_control.h.

const double simple_robot_control::Arm::wrist_speed_ = 2.0 [static, private]

Definition at line 66 of file arm_control.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


simple_robot_control
Author(s): Christian Bersch, Sebastian Haug
autogenerated on Fri Jan 11 10:10:10 2013