$search
#include <arm_control.h>
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 < arm_navigation_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 |
Definition at line 71 of file arm_control.h.
FRONTAL | |
FROM_BELOW | |
FROM_ABOVE | |
FROM_RIGHT_SIDEWAYS | |
FROM_RIGHT_UPRIGHT | |
FROM_LEFT_UPRIGHT | |
FROM_LEFT_SIDEWAYS |
Definition at line 140 of file arm_control.h.
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 18 of file arm_control.cpp.
simple_robot_control::Arm::~Arm | ( | ) |
Clean up the action client.
Definition at line 77 of file arm_control.cpp.
vector< double > simple_robot_control::Arm::getCurrentJointAngles | ( | ) |
get joint angles
Definition at line 212 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 217 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 261 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 266 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 103 of file arm_control.cpp.
tf::StampedTransform simple_robot_control::Arm::gripperToWrist | ( | const tf::StampedTransform & | pose | ) | [private] |
Definition at line 387 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 336 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 402 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 445 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 453 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 469 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 436 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 461 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 249 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 85 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 94 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 153 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 486 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 477 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 325 of file arm_control.cpp.
bool simple_robot_control::Arm::stretch | ( | ) |
Move arm into stretched out position.
Definition at line 367 of file arm_control.cpp.
bool simple_robot_control::Arm::tuck | ( | ) |
Move arm into tuck position.
Definition at line 348 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 308 of file arm_control.cpp.
tf::StampedTransform simple_robot_control::Arm::wristToGripper | ( | const tf::StampedTransform & | pose | ) | [private] |
Definition at line 394 of file arm_control.cpp.
string simple_robot_control::Arm::armside_str [private] |
Definition at line 79 of file arm_control.h.
vector<double> simple_robot_control::Arm::current_joint_angles_ [private] |
Definition at line 88 of file arm_control.h.
const double simple_robot_control::Arm::gripperlength = 0.18 [static, private] |
Definition at line 74 of file arm_control.h.
string simple_robot_control::Arm::group_name [private] |
Definition at line 80 of file arm_control.h.
Definition at line 84 of file arm_control.h.
vector<string> simple_robot_control::Arm::joint_names [private] |
Definition at line 78 of file arm_control.h.
actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction>* simple_robot_control::Arm::move_arm_client_ [private] |
Definition at line 81 of file arm_control.h.
Definition at line 85 of file arm_control.h.
actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > simple_robot_control::Arm::traj_client_ [private] |
Definition at line 82 of file arm_control.h.
const double simple_robot_control::Arm::wrist_speed_ = 2.0 [static, private] |
Definition at line 73 of file arm_control.h.