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

Class for working with collision objects. More...

#include <metablock.hpp>

List of all members.

Public Member Functions

tf::Stamped< tf::PosegetTransform (tf::TransformListener *listener, const std::string &frame)
 get the transform to base_link
geometry_msgs::PoseStamped getTransformed (tf::TransformListener *listener, const std::string &frame)
 get the transform to base_link
 MetaBlock (const std::string name, const geometry_msgs::Pose pose, const uint &shapeType, const float &size_x, const float &size_y, const float &size_z, ros::Time timestamp=ros::Time::now(), std::string base_frame="base_link")
 shape-based constructor
 MetaBlock (const std::string name, const geometry_msgs::Pose pose, const shape_msgs::Mesh mesh, const object_recognition_msgs::ObjectType type, ros::Time timestamp=ros::Time::now(), std::string base_frame="odom")
 mesh-based constructor
void publishBlock (mscene *current_scene)
 publish the collision object
void removeBlock (mscene *current_scene)
 remove the collision object
void updatePose (const geometry_msgs::Pose &pose)
 update the object pose
void updatePose (mscene *current_scene, const geometry_msgs::Pose &pose)
 update the pose and publish
void updatePoseVis (const geometry_msgs::Pose &pose)
 update the object's pose visually only

Public Attributes

std::string base_frame_
moveit_msgs::CollisionObject collObj_
geometry_msgs::Pose goal_pose_
std::string name_
geometry_msgs::Pose pose_
double size_x_
double size_y_
double size_z_
ros::Time timestamp_
object_recognition_msgs::ObjectType type_

Protected Attributes

shape_msgs::Mesh mesh_
shape_msgs::SolidPrimitive shape_

Detailed Description

Class for working with collision objects.

Definition at line 43 of file metablock.hpp.


Constructor & Destructor Documentation

moveit_simple_actions::MetaBlock::MetaBlock ( const std::string  name,
const geometry_msgs::Pose  pose,
const uint &  shapeType,
const float &  size_x,
const float &  size_y,
const float &  size_z,
ros::Time  timestamp = ros::Time::now(),
std::string  base_frame = "base_link" 
)

shape-based constructor

Definition at line 26 of file metablock.cpp.

moveit_simple_actions::MetaBlock::MetaBlock ( const std::string  name,
const geometry_msgs::Pose  pose,
const shape_msgs::Mesh  mesh,
const object_recognition_msgs::ObjectType  type,
ros::Time  timestamp = ros::Time::now(),
std::string  base_frame = "odom" 
)

mesh-based constructor

Definition at line 82 of file metablock.cpp.


Member Function Documentation

get the transform to base_link

Definition at line 164 of file metablock.cpp.

geometry_msgs::PoseStamped moveit_simple_actions::MetaBlock::getTransformed ( tf::TransformListener listener,
const std::string &  frame 
)

get the transform to base_link

Definition at line 198 of file metablock.cpp.

publish the collision object

Definition at line 144 of file metablock.cpp.

remove the collision object

Definition at line 135 of file metablock.cpp.

update the object pose

Definition at line 122 of file metablock.cpp.

void moveit_simple_actions::MetaBlock::updatePose ( mscene current_scene,
const geometry_msgs::Pose pose 
)

update the pose and publish

Definition at line 152 of file metablock.cpp.

update the object's pose visually only

Definition at line 129 of file metablock.cpp.


Member Data Documentation

the base frame

Definition at line 113 of file metablock.hpp.

moveit_msgs::CollisionObject moveit_simple_actions::MetaBlock::collObj_

corresponding collision object

Definition at line 98 of file metablock.hpp.

the goal position

Definition at line 95 of file metablock.hpp.

shape_msgs::Mesh moveit_simple_actions::MetaBlock::mesh_ [protected]

the object's mesh

Definition at line 123 of file metablock.hpp.

object name

Definition at line 89 of file metablock.hpp.

the current position

Definition at line 92 of file metablock.hpp.

shape_msgs::SolidPrimitive moveit_simple_actions::MetaBlock::shape_ [protected]

the object's shape

Definition at line 120 of file metablock.hpp.

x dimenssion

Definition at line 101 of file metablock.hpp.

y dimenssion

Definition at line 104 of file metablock.hpp.

z dimenssion

Definition at line 107 of file metablock.hpp.

timestamp of creation

Definition at line 110 of file metablock.hpp.

object_recognition_msgs::ObjectType moveit_simple_actions::MetaBlock::type_

corresponding object type in DB

Definition at line 116 of file metablock.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