turtlebot_arm_block_manipulation::PickAndPlaceServer::PickAndPlaceServer |
( |
const std::string |
name | ) |
|
|
inline |
float turtlebot_arm_block_manipulation::PickAndPlaceServer::fRand |
( |
float |
min, |
|
|
float |
max |
|
) |
| |
|
inlineprivate |
void turtlebot_arm_block_manipulation::PickAndPlaceServer::goalCB |
( |
| ) |
|
|
inline |
bool turtlebot_arm_block_manipulation::PickAndPlaceServer::moveArmTo |
( |
const std::string & |
target | ) |
|
|
inlineprivate |
Move arm to a named configuration, normally described in the robot semantic description SRDF file.
- Parameters
-
target | Named target to achieve |
- Returns
- True of success, false otherwise
Definition at line 187 of file pick_and_place_action_server.cpp.
bool turtlebot_arm_block_manipulation::PickAndPlaceServer::moveArmTo |
( |
const geometry_msgs::Pose & |
target | ) |
|
|
inlineprivate |
Move arm to a target pose. Only position coordinates are taken into account; the orientation is calculated according to the direction and distance to the target.
- Parameters
-
target | Pose target to achieve |
- Returns
- True of success, false otherwise
Definition at line 215 of file pick_and_place_action_server.cpp.
void turtlebot_arm_block_manipulation::PickAndPlaceServer::preemptCB |
( |
| ) |
|
|
inline |
void turtlebot_arm_block_manipulation::PickAndPlaceServer::sendGoalFromTopic |
( |
const geometry_msgs::PoseArrayConstPtr & |
msg | ) |
|
|
inline |
bool turtlebot_arm_block_manipulation::PickAndPlaceServer::setGripper |
( |
float |
opening | ) |
|
|
inlineprivate |
Set gripper opening.
- Parameters
-
opening | Physical opening of the gripper, in meters |
- Returns
- True of success, false otherwise
Definition at line 287 of file pick_and_place_action_server.cpp.
std::string turtlebot_arm_block_manipulation::PickAndPlaceServer::action_name_ |
|
private |
std::string turtlebot_arm_block_manipulation::PickAndPlaceServer::arm_link |
|
private |
double turtlebot_arm_block_manipulation::PickAndPlaceServer::attach_time |
|
private |
double turtlebot_arm_block_manipulation::PickAndPlaceServer::detach_time |
|
private |
turtlebot_arm_block_manipulation::PickAndPlaceFeedback turtlebot_arm_block_manipulation::PickAndPlaceServer::feedback_ |
|
private |
turtlebot_arm_block_manipulation::PickAndPlaceGoalConstPtr turtlebot_arm_block_manipulation::PickAndPlaceServer::goal_ |
|
private |
double turtlebot_arm_block_manipulation::PickAndPlaceServer::gripper_closed |
|
private |
double turtlebot_arm_block_manipulation::PickAndPlaceServer::gripper_open |
|
private |
ros::Subscriber turtlebot_arm_block_manipulation::PickAndPlaceServer::pick_and_place_sub_ |
|
private |
turtlebot_arm_block_manipulation::PickAndPlaceResult turtlebot_arm_block_manipulation::PickAndPlaceServer::result_ |
|
private |
ros::Publisher turtlebot_arm_block_manipulation::PickAndPlaceServer::target_pose_pub_ |
|
private |
double turtlebot_arm_block_manipulation::PickAndPlaceServer::z_up |
|
private |
The documentation for this class was generated from the following file: