Public Member Functions | Static Public Member Functions | Static Private Member Functions
object_msgs_tools::ObjectFunctions Class Reference

#include <ObjectFunctions.h>

List of all members.

Public Member Functions

 ObjectFunctions ()

Static Public Member Functions

static bool getObjectPose (const object_msgs::Object &object, geometry_msgs::PoseStamped &pose)

Static Private Member Functions

static geometry_msgs::Point getAveragePointFrom (const std::vector< geometry_msgs::Pose > &poses)
static bool getPoseFromFields (const std_msgs::Header &object_header, int idx, const std::vector< geometry_msgs::Pose > &poses, const geometry_msgs::Pose &origin, geometry_msgs::PoseStamped &pose)

Detailed Description

Provides a collection of convenience function for object_msgs/Object.

Author:
Jennifer Buehler
Date:
March 2016

Definition at line 16 of file ObjectFunctions.h.


Constructor & Destructor Documentation

Definition at line 20 of file ObjectFunctions.h.


Member Function Documentation

geometry_msgs::Point ObjectFunctions::getAveragePointFrom ( const std::vector< geometry_msgs::Pose > &  poses) [static, private]

Computes the average pose of several positions. Because the average of several quaternions can only be determined approximately when the quaternions are close together, the orientation parts are ignored, and only the position is returned.

Definition at line 65 of file ObjectFunctions.cpp.

bool ObjectFunctions::getObjectPose ( const object_msgs::Object &  object,
geometry_msgs::PoseStamped &  pose 
) [static]

Get the object pose out of the information in object according to what's specified in the message (fields object.primitive_origin and/or object.mesh_origin). If both mesh and primitive origins are enabled, the primitives are used to determine the object pose.

Returns:
false if insufficient information given to determine object pose, true if pose is returned in pose.

Definition at line 7 of file ObjectFunctions.cpp.

bool ObjectFunctions::getPoseFromFields ( const std_msgs::Header object_header,
int  idx,
const std::vector< geometry_msgs::Pose > &  poses,
const geometry_msgs::Pose origin,
geometry_msgs::PoseStamped &  pose 
) [static, private]
Parameters:
idxthe value of either Object::primitive_origin or Object::mesh_origin
object_headerthe header of the Object message.
posesthe poses, either Object::primitive_poses or Object::mesh_poses
originthe field Object::origin, in case it is required.

Definition at line 29 of file ObjectFunctions.cpp.


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


object_msgs_tools
Author(s): Jennifer Buehler
autogenerated on Mon Feb 25 2019 03:45:29