Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
moveit_simple_actions::Action Class Reference

Class for motion planning based on move_group. More...

#include <action.hpp>

List of all members.

Public Member Functions

 Action (ros::NodeHandle *nh, const std::string &arm, const std::string &robot_name, const std::string &base_frame)
 constructor
float computeDistance (MetaBlock *block)
 compute the distance to the object
float computeDistance (geometry_msgs::Pose goal)
 compute the distance to the pose
void detachObject (const std::string &block_name)
 detach the collision object
bool executeAction ()
 execute the planned motion trajectory
std::string getBaseLink ()
 get the base_link
geometry_msgs::PoseStamped getGraspPose (MetaBlock *block)
 get the grasping pose for the object pose
geometry_msgs::Pose getPose ()
 get the current pose
bool graspPlan (MetaBlock *block, const std::string surface_name)
 plan a trajectory as computePlanButtonClicked in MoveIt
bool graspPlanAllPossible (MetaBlock *block, const std::string surface_name)
 plan and show all possible motion trajectories
void initVisualTools (moveit_visual_tools::MoveItVisualToolsPtr &visual_tools)
 initialize the visual tools
bool pickAction (MetaBlock *block, const std::string surface_name, const int attempts_nbr=0, const double planning_time=0.0)
 pick an object with a grasp generator
bool pickDefault (MetaBlock *block, const std::string surface_name)
 pick an object without a grasp generator
bool placeAction (MetaBlock *block, const std::string surface_name)
 pick an object
bool poseHand (const int pose_id)
 go to the pose
void poseHandClose ()
 go to the pose that closes hand
void poseHandOpen ()
 go to the pose that opens hand
bool poseHeadDown ()
 go to the pose that moves the head down
bool poseHeadZero ()
 go to the pose that moves the head to zero
bool reachAction (geometry_msgs::PoseStamped pose_target, const std::string surface_name="", const int attempts_nbr=1)
 reach the top of an object
bool reachGrasp (MetaBlock *block, const std::string surface_name, int attempts_nbr=0, float tolerance_min=0.0f, double planning_time=0.0)
 reach default grasping pose
void releaseObject (MetaBlock *block)
 release the object
void setTolerance (const double value)
 set the tolerance

Public Attributes

const std::string plan_group_

Private Member Functions

void attachObject (const std::string &block_name)
 attach the collision object
std::vector< geometry_msgs::PoseconfigureForPlanning (const std::vector< moveit_msgs::Grasp > &grasps)
 configure for planning
std::vector< std::string >
::iterator 
ensureExistsInACM (const std::string &name, moveit_msgs::AllowedCollisionMatrix &m, bool initFlag)
 ensure that the entry exist in the collision matrix
void expandMoveItCollisionMatrix (const std::string &name, moveit_msgs::AllowedCollisionMatrix &m, bool default_val)
 add an object to the collision matrix
std::vector< moveit_msgs::Grasp > generateGrasps (MetaBlock *block)
 generate all possible grasps
bool getCurrentMoveItAllowedCollisionMatrix (moveit_msgs::AllowedCollisionMatrix &matrix)
 get allowed collision matrix
void publishPlanInfo (moveit::planning_interface::MoveGroup::Plan plan, geometry_msgs::Pose pose_target)
 publish the planning info
bool setAllowedMoveItCollisionMatrix (moveit_msgs::AllowedCollisionMatrix &m)
 set allowed collision matrix
void setAttemptsMax (int value)
 set the maximum number of attempts
void setFlag (int flag)
 set the flag if action execution is allowed
void setMaxVelocityScalingFactor (const double value)
 set the maximum velocity scaling factor
void setPlanningTime (const double value)
 set the planning time
void setToleranceMin (const double value)
 set the minimum tolerance
void setToleranceStep (const double value)
 set the tolerance step
void setVerbose (bool verbose)
 set verbosity
void updateCollisionMatrix (const std::string &name)
 update the collision matrix with the object

Private Attributes

std::vector< std::string > allowedCollisionLinks_
int attempts_max_
std::string base_frame_
ros::ServiceClient client_fk_
boost::shared_ptr
< moveit::planning_interface::MoveGroup::Plan
current_plan_
moveit::planning_interface::PlanningSceneInterface current_scene_
float dist_th_
const std::string end_eff_
int flag_
moveit_simple_grasps::GraspData grasp_data_
tf::TransformListener listener_
double max_velocity_scaling_factor_
boost::scoped_ptr
< move_group_interface::MoveGroup > 
move_group_
std::string object_attached_
std::string planner_id_
ros::ServiceClient planning_scene_client_
ros::Publisher planning_scene_publisher_
double planning_time_
Posture posture_
ros::Publisher pub_obj_pose_
ros::Publisher pub_plan_pose_
ros::Publisher pub_plan_traj_
moveit_simple_grasps::SimpleGraspsPtr simple_grasps_
double tolerance_min_
double tolerance_step_
bool verbose_
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_

Detailed Description

Class for motion planning based on move_group.

Definition at line 47 of file action.hpp.


Constructor & Destructor Documentation

moveit_simple_actions::Action::Action ( ros::NodeHandle nh,
const std::string &  arm,
const std::string &  robot_name,
const std::string &  base_frame 
)

constructor

Definition at line 29 of file action.cpp.


Member Function Documentation

void moveit_simple_actions::Action::attachObject ( const std::string &  block_name) [private]

attach the collision object

Definition at line 952 of file action.cpp.

compute the distance to the object

Definition at line 280 of file action.cpp.

compute the distance to the pose

Definition at line 289 of file action.cpp.

std::vector< geometry_msgs::Pose > moveit_simple_actions::Action::configureForPlanning ( const std::vector< moveit_msgs::Grasp > &  grasps) [private]

configure for planning

Definition at line 685 of file action.cpp.

void moveit_simple_actions::Action::detachObject ( const std::string &  block_name)

detach the collision object

Definition at line 947 of file action.cpp.

std::vector< std::string >::iterator moveit_simple_actions::Action::ensureExistsInACM ( const std::string &  name,
moveit_msgs::AllowedCollisionMatrix &  m,
bool  initFlag 
) [private]

ensure that the entry exist in the collision matrix

Definition at line 415 of file action.cpp.

execute the planned motion trajectory

Definition at line 194 of file action.cpp.

void moveit_simple_actions::Action::expandMoveItCollisionMatrix ( const std::string &  name,
moveit_msgs::AllowedCollisionMatrix &  m,
bool  default_val 
) [private]

add an object to the collision matrix

Definition at line 435 of file action.cpp.

std::vector< moveit_msgs::Grasp > moveit_simple_actions::Action::generateGrasps ( MetaBlock block) [private]

generate all possible grasps

Definition at line 648 of file action.cpp.

get the base_link

Definition at line 957 of file action.cpp.

bool moveit_simple_actions::Action::getCurrentMoveItAllowedCollisionMatrix ( moveit_msgs::AllowedCollisionMatrix &  matrix) [private]

get allowed collision matrix

Definition at line 392 of file action.cpp.

geometry_msgs::PoseStamped moveit_simple_actions::Action::getGraspPose ( MetaBlock block)

get the grasping pose for the object pose

Definition at line 252 of file action.cpp.

get the current pose

Definition at line 330 of file action.cpp.

bool moveit_simple_actions::Action::graspPlan ( MetaBlock block,
const std::string  surface_name 
)

plan a trajectory as computePlanButtonClicked in MoveIt

Definition at line 215 of file action.cpp.

bool moveit_simple_actions::Action::graspPlanAllPossible ( MetaBlock block,
const std::string  surface_name 
)

plan and show all possible motion trajectories

Definition at line 605 of file action.cpp.

initialize the visual tools

Definition at line 119 of file action.cpp.

bool moveit_simple_actions::Action::pickAction ( MetaBlock block,
const std::string  surface_name,
const int  attempts_nbr = 0,
const double  planning_time = 0.0 
)

pick an object with a grasp generator

Definition at line 703 of file action.cpp.

bool moveit_simple_actions::Action::pickDefault ( MetaBlock block,
const std::string  surface_name 
)

pick an object without a grasp generator

Definition at line 127 of file action.cpp.

bool moveit_simple_actions::Action::placeAction ( MetaBlock block,
const std::string  surface_name 
)

pick an object

Definition at line 760 of file action.cpp.

bool moveit_simple_actions::Action::poseHand ( const int  pose_id)

go to the pose

Definition at line 311 of file action.cpp.

go to the pose that closes hand

Definition at line 325 of file action.cpp.

go to the pose that opens hand

Definition at line 320 of file action.cpp.

go to the pose that moves the head down

Definition at line 306 of file action.cpp.

go to the pose that moves the head to zero

Definition at line 301 of file action.cpp.

publish the planning info

Definition at line 828 of file action.cpp.

bool moveit_simple_actions::Action::reachAction ( geometry_msgs::PoseStamped  pose_target,
const std::string  surface_name = "",
const int  attempts_nbr = 1 
)

reach the top of an object

Definition at line 536 of file action.cpp.

bool moveit_simple_actions::Action::reachGrasp ( MetaBlock block,
const std::string  surface_name,
int  attempts_nbr = 0,
float  tolerance_min = 0.0f,
double  planning_time = 0.0 
)

reach default grasping pose

Definition at line 473 of file action.cpp.

release the object

Definition at line 357 of file action.cpp.

bool moveit_simple_actions::Action::setAllowedMoveItCollisionMatrix ( moveit_msgs::AllowedCollisionMatrix &  m) [private]

set allowed collision matrix

Definition at line 377 of file action.cpp.

void moveit_simple_actions::Action::setAttemptsMax ( int  value) [private]

set the maximum number of attempts

Definition at line 927 of file action.cpp.

void moveit_simple_actions::Action::setFlag ( int  flag) [private]

set the flag if action execution is allowed

Definition at line 934 of file action.cpp.

void moveit_simple_actions::Action::setMaxVelocityScalingFactor ( const double  value) [private]

set the maximum velocity scaling factor

Definition at line 912 of file action.cpp.

void moveit_simple_actions::Action::setPlanningTime ( const double  value) [private]

set the planning time

Definition at line 890 of file action.cpp.

void moveit_simple_actions::Action::setTolerance ( const double  value)

set the tolerance

Definition at line 349 of file action.cpp.

void moveit_simple_actions::Action::setToleranceMin ( const double  value) [private]

set the minimum tolerance

Definition at line 905 of file action.cpp.

void moveit_simple_actions::Action::setToleranceStep ( const double  value) [private]

set the tolerance step

Definition at line 898 of file action.cpp.

void moveit_simple_actions::Action::setVerbose ( bool  verbose) [private]

set verbosity

Definition at line 920 of file action.cpp.

void moveit_simple_actions::Action::updateCollisionMatrix ( const std::string &  name) [private]

update the collision matrix with the object

Definition at line 452 of file action.cpp.


Member Data Documentation

std::vector<std::string> moveit_simple_actions::Action::allowedCollisionLinks_ [private]

allowed collision links

Definition at line 270 of file action.hpp.

maximum number of attempts to do action

Definition at line 234 of file action.hpp.

base frame

Definition at line 273 of file action.hpp.

client FK

Definition at line 228 of file action.hpp.

for planning actions

Definition at line 210 of file action.hpp.

the current MoveIt scene

Definition at line 216 of file action.hpp.

the the distance to object allowing to grasp it

Definition at line 252 of file action.hpp.

const std::string moveit_simple_actions::Action::end_eff_ [private]

active end effector

Definition at line 195 of file action.hpp.

flag to allow motion

Definition at line 255 of file action.hpp.

grasp configuration

Definition at line 201 of file action.hpp.

the transform listener

Definition at line 261 of file action.hpp.

maximum velocity factor

Definition at line 249 of file action.hpp.

boost::scoped_ptr<move_group_interface::MoveGroup> moveit_simple_actions::Action::move_group_ [private]

interface with MoveIt

Definition at line 204 of file action.hpp.

the current attached object

Definition at line 258 of file action.hpp.

name of the planning group

Definition at line 136 of file action.hpp.

planning library

Definition at line 240 of file action.hpp.

planning scene client

Definition at line 267 of file action.hpp.

client get scene difference

Definition at line 264 of file action.hpp.

planning time

Definition at line 237 of file action.hpp.

posture class

Definition at line 198 of file action.hpp.

publisher for a pre-grasp pose

Definition at line 219 of file action.hpp.

publish final pose

Definition at line 222 of file action.hpp.

publish final trajectory

Definition at line 225 of file action.hpp.

grasp generator

Definition at line 207 of file action.hpp.

minimum tolerance to reach

Definition at line 243 of file action.hpp.

the tolerance step to vary

Definition at line 246 of file action.hpp.

verbnosity level

Definition at line 231 of file action.hpp.

visual tools pointer used for scene visualization

Definition at line 213 of file action.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