Public Member Functions | Protected Member Functions | Protected Attributes
moveit_simple_actions::SimplePickPlace Class Reference

Class for running the main pipeline. More...

#include <simplepickplace.hpp>

List of all members.

Public Member Functions

void run ()
 main cycle
 SimplePickPlace (const std::string robot_name, const double test_step, const double x_min, const double x_max, const double y_min, const double y_max, const double z_min, const double z_max, const std::string left_arm_name, const std::string right_arm_name, const bool verbose)
 constructor

Protected Member Functions

bool checkObj (int &block_id)
 check if the block exists
void cleanObjects (std::vector< MetaBlock > *objects, const bool list_erase=true)
 clean the object list based on the timestamp
void createObj (const MetaBlock &block)
 create and publish an object
MetaBlock createTable ()
 create a table object
void getCollisionObjects (const moveit_msgs::CollisionObject::ConstPtr &msg)
 get collision objects from the topic /collision_object
void resetBlock (MetaBlock *block)
 publish the object at new position
void switchArm (Action *action_now)
 switch between the left and right arms

Protected Attributes

Actionaction_left_
Actionaction_right_
std::string base_frame_
double block_size_x_
double block_size_y_
std::vector< MetaBlockblocks_surfaces_
moveit::planning_interface::PlanningSceneInterface current_scene_
bool env_shown_
Evaluation evaluation_
double floor_to_base_height_
geometry_msgs::PoseStamped msg_obj_pose_
ros::NodeHandle nh_
ros::NodeHandle nh_priv_
ObjProcessor obj_proc_
geometry_msgs::Pose pose_default_
geometry_msgs::Pose pose_default_r_
geometry_msgs::Pose pose_zero_
ros::Publisher pub_obj_moveit_
ros::Publisher pub_obj_pose_
ros::Rate rate_
std::string robot_name_
std::vector< geometry_msgs::Posestat_poses_success_
ros::Subscriber sub_obj_coll_
std::string support_surface_
const bool verbose_
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_
double x_max_
double x_min_
double y_max_
double y_min_
double z_max_
double z_min_

Detailed Description

Class for running the main pipeline.

Definition at line 33 of file simplepickplace.hpp.


Constructor & Destructor Documentation

moveit_simple_actions::SimplePickPlace::SimplePickPlace ( const std::string  robot_name,
const double  test_step,
const double  x_min,
const double  x_max,
const double  y_min,
const double  y_max,
const double  z_min,
const double  z_max,
const std::string  left_arm_name,
const std::string  right_arm_name,
const bool  verbose 
)

constructor

Definition at line 51 of file simplepickplace.cpp.


Member Function Documentation

bool moveit_simple_actions::SimplePickPlace::checkObj ( int &  block_id) [protected]

check if the block exists

Definition at line 207 of file simplepickplace.cpp.

void moveit_simple_actions::SimplePickPlace::cleanObjects ( std::vector< MetaBlock > *  objects,
const bool  list_erase = true 
) [protected]

clean the object list based on the timestamp

Definition at line 583 of file simplepickplace.cpp.

void moveit_simple_actions::SimplePickPlace::createObj ( const MetaBlock block) [protected]

create and publish an object

Definition at line 196 of file simplepickplace.cpp.

create a table object

Definition at line 30 of file simplepickplace.cpp.

void moveit_simple_actions::SimplePickPlace::getCollisionObjects ( const moveit_msgs::CollisionObject::ConstPtr &  msg) [protected]

get collision objects from the topic /collision_object

publish the object at new position

Definition at line 594 of file simplepickplace.cpp.

main cycle

Definition at line 215 of file simplepickplace.cpp.

void moveit_simple_actions::SimplePickPlace::switchArm ( Action action_now) [protected]

switch between the left and right arms

Definition at line 185 of file simplepickplace.cpp.


Member Data Documentation

instance of an Action class for the left arm

Definition at line 117 of file simplepickplace.hpp.

instance of an Action class for the right arm

Definition at line 120 of file simplepickplace.hpp.

robot's base_frame

Definition at line 85 of file simplepickplace.hpp.

dimenssion x of a default object

Definition at line 88 of file simplepickplace.hpp.

dimenssion y of a default object

Definition at line 91 of file simplepickplace.hpp.

set of available surfaces

Definition at line 129 of file simplepickplace.hpp.

current MoveIt scene

Definition at line 126 of file simplepickplace.hpp.

state of re-drawing the world

Definition at line 103 of file simplepickplace.hpp.

evaluation of reaching/grasping

Definition at line 100 of file simplepickplace.hpp.

shift of the robot's base to the floor

Definition at line 94 of file simplepickplace.hpp.

geometry_msgs::PoseStamped moveit_simple_actions::SimplePickPlace::msg_obj_pose_ [protected]

current object position

Definition at line 138 of file simplepickplace.hpp.

node handle

Definition at line 76 of file simplepickplace.hpp.

Definition at line 76 of file simplepickplace.hpp.

object processing

Definition at line 97 of file simplepickplace.hpp.

default object pose for the left arm

Definition at line 141 of file simplepickplace.hpp.

default object pose for the right arm

Definition at line 144 of file simplepickplace.hpp.

default object pose at zero

Definition at line 147 of file simplepickplace.hpp.

publisher of collision objects to /collision_world

Definition at line 153 of file simplepickplace.hpp.

publisher of the current object pose

Definition at line 135 of file simplepickplace.hpp.

processing rate

Definition at line 156 of file simplepickplace.hpp.

robot's name

Definition at line 79 of file simplepickplace.hpp.

all successfully reached positions

Definition at line 150 of file simplepickplace.hpp.

subscriber to get objects from /collision_object

Definition at line 132 of file simplepickplace.hpp.

name of the current support surface

Definition at line 114 of file simplepickplace.hpp.

verbosity

Definition at line 82 of file simplepickplace.hpp.

visual tools pointer used for scene visualization

Definition at line 123 of file simplepickplace.hpp.

Definition at line 107 of file simplepickplace.hpp.

Definition at line 106 of file simplepickplace.hpp.

Definition at line 109 of file simplepickplace.hpp.

Definition at line 108 of file simplepickplace.hpp.

Definition at line 111 of file simplepickplace.hpp.

Definition at line 110 of file simplepickplace.hpp.


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


romeo_moveit_actions
Author(s):
autogenerated on Thu Jun 6 2019 21:57:24