#include <common_actions.h>
Public Member Functions | |
CommonActions () | |
Constructor. | |
Private Member Functions | |
void | executeArmAction (const rail_manipulation_msgs::ArmGoalConstPtr &goal) |
Move arm to a defined position with obstacle avoidance. | |
void | executePickup (const rail_manipulation_msgs::PickupGoalConstPtr &goal) |
Perform a pickup action. | |
void | executeStore (const rail_manipulation_msgs::StoreGoalConstPtr &goal) |
Perform a store action. | |
void | executeWipeSurface (const carl_moveit::WipeSurfaceGoalConstPtr &goal) |
bool | isArmRetracted (const std::vector< float > &retractPos) |
determine if the arm is currently retracted in a given retracted position | |
void | liftArm (const rail_manipulation_msgs::LiftGoalConstPtr &goal) |
Raise the hand vertically by 10 cm. | |
Private Attributes | |
ros::Publisher | angularCmdPublisher |
actionlib::SimpleActionServer < rail_manipulation_msgs::ArmAction > | armServer |
ros::ServiceClient | attachClosestObjectClient |
ros::ServiceClient | cartesianPathClient |
std::vector< float > | defaultRetractPosition |
ros::ServiceClient | detachObjectsClient |
ros::ServiceClient | eraseTrajectoriesClient |
actionlib::SimpleActionClient < rail_manipulation_msgs::GripperAction > | gripperClient |
std::vector< float > | homePosition |
ros::ServiceClient | jacoPosClient |
actionlib::SimpleActionClient < rail_manipulation_msgs::LiftAction > | liftClient |
actionlib::SimpleActionServer < rail_manipulation_msgs::LiftAction > | liftServer |
actionlib::SimpleActionClient < rail_manipulation_msgs::MoveToJointPoseAction > | moveToJointPoseClient |
actionlib::SimpleActionClient < rail_manipulation_msgs::MoveToPoseAction > | moveToPoseClient |
ros::NodeHandle | n |
actionlib::SimpleActionServer < rail_manipulation_msgs::PickupAction > | pickupServer |
actionlib::SimpleActionServer < rail_manipulation_msgs::StoreAction > | storeServer |
tf::TransformBroadcaster | tfBroadcaster |
tf::TransformListener | tfListener |
actionlib::SimpleActionServer < carl_moveit::WipeSurfaceAction > | wipeSurfaceServer |
Definition at line 26 of file common_actions.h.
Constructor.
Definition at line 5 of file common_actions.cpp.
void CommonActions::executeArmAction | ( | const rail_manipulation_msgs::ArmGoalConstPtr & | goal | ) | [private] |
Move arm to a defined position with obstacle avoidance.
Action server to execute pre-defined arm actions, such as moving to the ready (JACO home) position, or moving to a retracted position.
goal | Specification of the arm action to be executed. |
Definition at line 283 of file common_actions.cpp.
void CommonActions::executePickup | ( | const rail_manipulation_msgs::PickupGoalConstPtr & | goal | ) | [private] |
Perform a pickup action.
A pickup action with CARL consists of sequentially executing the following actions: move to approach angle, open gripper, move along approach angle to the grasp pose, close gripper, optionally lift the object, and optionally verify that it is in-hand.
goal | Grasp pose with which to execute the pickup |
Definition at line 49 of file common_actions.cpp.
void CommonActions::executeStore | ( | const rail_manipulation_msgs::StoreGoalConstPtr & | goal | ) | [private] |
Perform a store action.
A store action with CARL consists of moving the end effector above the storage location on CARL's platform, lowering the end effector, opening the gripper to release the object, and raising the end effector.
goal | Empty store goal |
Definition at line 174 of file common_actions.cpp.
void CommonActions::executeWipeSurface | ( | const carl_moveit::WipeSurfaceGoalConstPtr & | goal | ) | [private] |
Definition at line 451 of file common_actions.cpp.
bool CommonActions::isArmRetracted | ( | const std::vector< float > & | retractPos | ) | [private] |
determine if the arm is currently retracted in a given retracted position
retractPos | vector of joint states the make up a retracted position |
Definition at line 562 of file common_actions.cpp.
void CommonActions::liftArm | ( | const rail_manipulation_msgs::LiftGoalConstPtr & | goal | ) | [private] |
Raise the hand vertically by 10 cm.
goal | empty goal |
Definition at line 530 of file common_actions.cpp.
Definition at line 38 of file common_actions.h.
actionlib::SimpleActionServer<rail_manipulation_msgs::ArmAction> CommonActions::armServer [private] |
Definition at line 51 of file common_actions.h.
Definition at line 43 of file common_actions.h.
Definition at line 41 of file common_actions.h.
std::vector<float> CommonActions::defaultRetractPosition [private] |
Definition at line 60 of file common_actions.h.
Definition at line 44 of file common_actions.h.
Definition at line 40 of file common_actions.h.
actionlib::SimpleActionClient<rail_manipulation_msgs::GripperAction> CommonActions::gripperClient [private] |
Definition at line 48 of file common_actions.h.
std::vector<float> CommonActions::homePosition [private] |
Definition at line 59 of file common_actions.h.
Definition at line 42 of file common_actions.h.
actionlib::SimpleActionClient<rail_manipulation_msgs::LiftAction> CommonActions::liftClient [private] |
Definition at line 49 of file common_actions.h.
actionlib::SimpleActionServer<rail_manipulation_msgs::LiftAction> CommonActions::liftServer [private] |
Definition at line 50 of file common_actions.h.
actionlib::SimpleActionClient<rail_manipulation_msgs::MoveToJointPoseAction> CommonActions::moveToJointPoseClient [private] |
Definition at line 46 of file common_actions.h.
actionlib::SimpleActionClient<rail_manipulation_msgs::MoveToPoseAction> CommonActions::moveToPoseClient [private] |
Definition at line 47 of file common_actions.h.
ros::NodeHandle CommonActions::n [private] |
Definition at line 37 of file common_actions.h.
actionlib::SimpleActionServer<rail_manipulation_msgs::PickupAction> CommonActions::pickupServer [private] |
Definition at line 52 of file common_actions.h.
actionlib::SimpleActionServer<rail_manipulation_msgs::StoreAction> CommonActions::storeServer [private] |
Definition at line 53 of file common_actions.h.
Definition at line 56 of file common_actions.h.
Definition at line 57 of file common_actions.h.
actionlib::SimpleActionServer<carl_moveit::WipeSurfaceAction> CommonActions::wipeSurfaceServer [private] |
Definition at line 54 of file common_actions.h.