Public Types | Public Member Functions | Protected Member Functions | Private Attributes
walk_msgs::AbstractNode< T, U, S > Class Template Reference

Walking trajectory abstract node. More...

#include <abstract-node.hh>

List of all members.

Public Types

typedef U footprintRosType_t
 ROS footprint type.
typedef T patternGenerator_t
 pattern generatoe type
typedef S serviceRosType_t
 ROS service type.

Public Member Functions

 AbstractNode (const std::string &rosNamespace, const std::string &frameWorldId, bool enableService=true)
 Constructor.
 AbstractNode (const std::string &rosNamespace, const std::string &frameWorldId, const patternGenerator_t &pg, bool enableService=true)
 Constructor copying a given pattern generator into the node.
void spin ()
 Run the node. Returns when the node is exiting.
 ~AbstractNode ()
 Destructor.

Protected Member Functions

virtual void convertFootprint (typename patternGenerator_t::footprints_t &dst, const std::vector< footprintRosType_t > &src)=0
 Convert ROS footprint representation into the corresponding C++ representation.
bool getPath (typename serviceRosType_t::Request &req, typename serviceRosType_t::Response &res)
 getPath service callback
patternGenerator_tpatternGenerator ()
 Pattern generator getter.
void prepareTopicsData (typename serviceRosType_t::Response &res, bool startWithLeftFoot)
 Fill attributes with data which will be published.
virtual void setupPatternGenerator (typename serviceRosType_t::Request &req)=0
 Pattern generator specific setup.
void writeMotionAsParameter ()
 Write the motion as a parameter of the parameter server.

Private Attributes

nav_msgs::Path comPath_
 Center of mass path.
ros::Publisher comPub_
 Center of mass path publisher.
double footPrintHeight_
 Footprint height in MarkerArray (/footprints) message.
visualization_msgs::MarkerArray footprints_
 Marker array containing footprints data.
ros::Publisher footprintsPub_
 Footprints publisher.
double footPrintWidth_
 Footprint width in MarkerArray (/footprints) message.
std::string frameName_
 World frame id.
ros::ServiceServer getPathSrv_
 GetPath service.
nav_msgs::Path leftFootPath_
 Left foot path.
ros::Publisher leftFootPub_
 Left foot path publisher.
ros::NodeHandle nodeHandle_
 Main node handle.
std::string parameterName_
 Parameter in which the trajectory is stored.
patternGenerator_t patternGenerator_
 Pattern generator instance used to generate the trajectories.
ros::Rate rate_
 Topic publishing rate.
nav_msgs::Path rightFootPath_
 Right foot path.
ros::Publisher rightFootPub_
 Right foot path publisher.
nav_msgs::Path zmpPath_
 Zero Momentum point path.
ros::Publisher zmpPub_
 Zero Momentum Point path publisher.

Detailed Description

template<typename T, typename U, typename S>
class walk_msgs::AbstractNode< T, U, S >

Walking trajectory abstract node.

This class provides the skeleton of a generator node. A generator node provides the GetPath service which allows to ask remotely for walking trajectory computation.

This node also published the data as topics in order to allow their display in rviz for instance.

walking_trajectories.vcg at this package root level is a rviz configuration file which can be used to display walking trajectories.

Template Parameters:
Tpattern generator type
UROS footprint message type
SROS service type

Definition at line 31 of file abstract-node.hh.


Member Typedef Documentation

template<typename T, typename U, typename S>
typedef U walk_msgs::AbstractNode< T, U, S >::footprintRosType_t

ROS footprint type.

Definition at line 37 of file abstract-node.hh.

template<typename T, typename U, typename S>
typedef T walk_msgs::AbstractNode< T, U, S >::patternGenerator_t

pattern generatoe type

Definition at line 35 of file abstract-node.hh.

template<typename T, typename U, typename S>
typedef S walk_msgs::AbstractNode< T, U, S >::serviceRosType_t

ROS service type.

Definition at line 40 of file abstract-node.hh.


Constructor & Destructor Documentation

template<typename T, typename U, typename S>
walk_msgs::AbstractNode< T, U, S >::AbstractNode ( const std::string &  rosNamespace,
const std::string &  frameWorldId,
bool  enableService = true 
) [explicit]

Constructor.

Parameters:
rosNamespacenamespace used to initialize the ROS handle
frameWorldIdframe id in which the trajectories are expressed
enableServiceenable getPath service registration
template<typename T, typename U, typename S>
walk_msgs::AbstractNode< T, U, S >::AbstractNode ( const std::string &  rosNamespace,
const std::string &  frameWorldId,
const patternGenerator_t pg,
bool  enableService = true 
) [explicit]

Constructor copying a given pattern generator into the node.

This constructor is needed when a pattern generator requires arguments during instantiation. In this case, the default constructor will not work.

Warning:
the given pattern generator must be copyable.
Parameters:
rosNamespacenamespace used to initialize the ROS handle
frameWorldIdframe id in which the trajectories are expressed
pgpattern generator to be copied into this object
enableServiceenable getPath service registration
template<typename T, typename U, typename S>
walk_msgs::AbstractNode< T, U, S >::~AbstractNode ( )

Destructor.


Member Function Documentation

template<typename T, typename U, typename S>
virtual void walk_msgs::AbstractNode< T, U, S >::convertFootprint ( typename patternGenerator_t::footprints_t &  dst,
const std::vector< footprintRosType_t > &  src 
) [protected, pure virtual]

Convert ROS footprint representation into the corresponding C++ representation.

Subclasses must implement this method.

Implemented in GeneratorYamlNode.

template<typename T, typename U, typename S>
bool walk_msgs::AbstractNode< T, U, S >::getPath ( typename serviceRosType_t::Request &  req,
typename serviceRosType_t::Response &  res 
) [protected]

getPath service callback

This fill the pattern generator with data from the request, compute the trajectories by calling the computeTrajectories method and then both put the result in a ROS parameter and publish a displayable version into various separated topics.

Parameters:
reqservice request (i.e. input)
resservice response (i.e. output)
template<typename T, typename U, typename S>
patternGenerator_t& walk_msgs::AbstractNode< T, U, S >::patternGenerator ( ) [inline, protected]

Pattern generator getter.

Definition at line 109 of file abstract-node.hh.

template<typename T, typename U, typename S>
void walk_msgs::AbstractNode< T, U, S >::prepareTopicsData ( typename serviceRosType_t::Response &  res,
bool  startWithLeftFoot 
) [protected]

Fill attributes with data which will be published.

template<typename T, typename U, typename S>
virtual void walk_msgs::AbstractNode< T, U, S >::setupPatternGenerator ( typename serviceRosType_t::Request &  req) [protected, pure virtual]

Pattern generator specific setup.

Pattern generators often needs specific data to be passed or dedicated conversion to be made.

The getPath callback first fill the pattern generator with data common to all the pattern generators algorithm then calls the setupPatternGenerator method so that specific treatments can be realized.

Parameters:
reqrequest passed to the service callback

Implemented in GeneratorYamlNode.

template<typename T, typename U, typename S>
void walk_msgs::AbstractNode< T, U, S >::spin ( )

Run the node. Returns when the node is exiting.

template<typename T, typename U, typename S>
void walk_msgs::AbstractNode< T, U, S >::writeMotionAsParameter ( ) [protected]

Write the motion as a parameter of the parameter server.


Member Data Documentation

template<typename T, typename U, typename S>
nav_msgs::Path walk_msgs::AbstractNode< T, U, S >::comPath_ [private]

Center of mass path.

Definition at line 153 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::Publisher walk_msgs::AbstractNode< T, U, S >::comPub_ [private]

Center of mass path publisher.

Definition at line 164 of file abstract-node.hh.

template<typename T, typename U, typename S>
double walk_msgs::AbstractNode< T, U, S >::footPrintHeight_ [private]

Footprint height in MarkerArray (/footprints) message.

Definition at line 171 of file abstract-node.hh.

template<typename T, typename U, typename S>
visualization_msgs::MarkerArray walk_msgs::AbstractNode< T, U, S >::footprints_ [private]

Marker array containing footprints data.

Definition at line 145 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::Publisher walk_msgs::AbstractNode< T, U, S >::footprintsPub_ [private]

Footprints publisher.

Definition at line 158 of file abstract-node.hh.

template<typename T, typename U, typename S>
double walk_msgs::AbstractNode< T, U, S >::footPrintWidth_ [private]

Footprint width in MarkerArray (/footprints) message.

Definition at line 169 of file abstract-node.hh.

template<typename T, typename U, typename S>
std::string walk_msgs::AbstractNode< T, U, S >::frameName_ [private]

World frame id.

All walking trajectories are expressed w.r.t this frame.

Definition at line 135 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::ServiceServer walk_msgs::AbstractNode< T, U, S >::getPathSrv_ [private]

GetPath service.

Definition at line 130 of file abstract-node.hh.

template<typename T, typename U, typename S>
nav_msgs::Path walk_msgs::AbstractNode< T, U, S >::leftFootPath_ [private]

Left foot path.

Definition at line 148 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::Publisher walk_msgs::AbstractNode< T, U, S >::leftFootPub_ [private]

Left foot path publisher.

Definition at line 160 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::NodeHandle walk_msgs::AbstractNode< T, U, S >::nodeHandle_ [private]

Main node handle.

Definition at line 124 of file abstract-node.hh.

template<typename T, typename U, typename S>
std::string walk_msgs::AbstractNode< T, U, S >::parameterName_ [private]

Parameter in which the trajectory is stored.

Definition at line 138 of file abstract-node.hh.

template<typename T, typename U, typename S>
patternGenerator_t walk_msgs::AbstractNode< T, U, S >::patternGenerator_ [private]

Pattern generator instance used to generate the trajectories.

Definition at line 142 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::Rate walk_msgs::AbstractNode< T, U, S >::rate_ [private]

Topic publishing rate.

Definition at line 127 of file abstract-node.hh.

template<typename T, typename U, typename S>
nav_msgs::Path walk_msgs::AbstractNode< T, U, S >::rightFootPath_ [private]

Right foot path.

Definition at line 150 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::Publisher walk_msgs::AbstractNode< T, U, S >::rightFootPub_ [private]

Right foot path publisher.

Definition at line 162 of file abstract-node.hh.

template<typename T, typename U, typename S>
nav_msgs::Path walk_msgs::AbstractNode< T, U, S >::zmpPath_ [private]

Zero Momentum point path.

Definition at line 155 of file abstract-node.hh.

template<typename T, typename U, typename S>
ros::Publisher walk_msgs::AbstractNode< T, U, S >::zmpPub_ [private]

Zero Momentum Point path publisher.

Definition at line 166 of file abstract-node.hh.


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


walk_msgs
Author(s): Thomas Moulard
autogenerated on Sat Dec 28 2013 17:05:25