Public Member Functions | Private Attributes | List of all members
BlockManipulationAction Class Reference

Public Member Functions

void addBlock (float x, float y, float z, int n)
 
void addBlocks (const actionlib::SimpleClientGoalState &state, const turtlebot_arm_block_manipulation::BlockDetectionResultConstPtr &result)
 
 BlockManipulationAction ()
 
void detectBlocks ()
 
void feedbackCb (const InteractiveMarkerFeedbackConstPtr &feedback)
 
Marker makeBox (InteractiveMarker &msg, float r, float g, float b)
 
bool moveBlock (const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)
 

Private Attributes

actionlib::SimpleActionClient< turtlebot_arm_block_manipulation::BlockDetectionAction > block_detection_action_
 
turtlebot_arm_block_manipulation::BlockDetectionGoal block_detection_goal_
 
ros::NodeHandle nh_
 
geometry_msgs::Pose old_pose_
 
actionlib::SimpleActionClient< turtlebot_arm_block_manipulation::PickAndPlaceAction > pick_and_place_action_
 
turtlebot_arm_block_manipulation::PickAndPlaceGoal pick_and_place_goal_
 
interactive_markers::InteractiveMarkerServer server_
 

Detailed Description

Definition at line 52 of file block_manipulation_actions.cpp.

Constructor & Destructor Documentation

BlockManipulationAction::BlockManipulationAction ( )
inline

Definition at line 70 of file block_manipulation_actions.cpp.

Member Function Documentation

void BlockManipulationAction::addBlock ( float  x,
float  y,
float  z,
int  n 
)
inline

Definition at line 177 of file block_manipulation_actions.cpp.

void BlockManipulationAction::addBlocks ( const actionlib::SimpleClientGoalState state,
const turtlebot_arm_block_manipulation::BlockDetectionResultConstPtr &  result 
)
inline

Definition at line 105 of file block_manipulation_actions.cpp.

void BlockManipulationAction::detectBlocks ( )
inline

Definition at line 97 of file block_manipulation_actions.cpp.

void BlockManipulationAction::feedbackCb ( const InteractiveMarkerFeedbackConstPtr &  feedback)
inline

Definition at line 122 of file block_manipulation_actions.cpp.

Marker BlockManipulationAction::makeBox ( InteractiveMarker &  msg,
float  r,
float  g,
float  b 
)
inline

Definition at line 160 of file block_manipulation_actions.cpp.

bool BlockManipulationAction::moveBlock ( const geometry_msgs::Pose start_pose,
const geometry_msgs::Pose end_pose 
)
inline

Definition at line 141 of file block_manipulation_actions.cpp.

Member Data Documentation

actionlib::SimpleActionClient<turtlebot_arm_block_manipulation::BlockDetectionAction> BlockManipulationAction::block_detection_action_
private

Definition at line 60 of file block_manipulation_actions.cpp.

turtlebot_arm_block_manipulation::BlockDetectionGoal BlockManipulationAction::block_detection_goal_
private

Definition at line 63 of file block_manipulation_actions.cpp.

ros::NodeHandle BlockManipulationAction::nh_
private

Definition at line 57 of file block_manipulation_actions.cpp.

geometry_msgs::Pose BlockManipulationAction::old_pose_
private

Definition at line 66 of file block_manipulation_actions.cpp.

actionlib::SimpleActionClient<turtlebot_arm_block_manipulation::PickAndPlaceAction> BlockManipulationAction::pick_and_place_action_
private

Definition at line 61 of file block_manipulation_actions.cpp.

turtlebot_arm_block_manipulation::PickAndPlaceGoal BlockManipulationAction::pick_and_place_goal_
private

Definition at line 64 of file block_manipulation_actions.cpp.

interactive_markers::InteractiveMarkerServer BlockManipulationAction::server_
private

Definition at line 55 of file block_manipulation_actions.cpp.


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


turtlebot_arm_block_manipulation
Author(s): Michael Ferguson, Helen Oleynikova
autogenerated on Fri Feb 7 2020 03:56:21