Tetrapod Project
gazebo::FootstepPlannerPlugin Class Reference

#include <footstep_planner_plugin.h>

Inheritance diagram for gazebo::FootstepPlannerPlugin:
Collaboration diagram for gazebo::FootstepPlannerPlugin:

Public Member Functions

 FootstepPlannerPlugin ()
 
virtual ~FootstepPlannerPlugin ()
 
virtual void Load (physics::WorldPtr _world, sdf::ElementPtr _sdf)
 The Load function is called by Gazebo when the plugin is inserted into simulation. More...
 
void UpdateFootstepPlan (const geometry_msgs::PoseArray::ConstPtr &msg)
 
void InitRos ()
 
void InitRosQueueThreads ()
 
void ProcessQueueThread ()
 
void InitGazebo ()
 
void DeleteVisuals ()
 
void SetVisuals (Eigen::MatrixX3d &poses)
 
void PublishVisuals ()
 

Private Attributes

physics::WorldPtr world
 Pointer to the world. More...
 
std::unique_ptr< ros::NodeHandle > rosNode
 Node used for ROS transport. More...
 
ros::Subscriber footstepPlannerSub
 
ros::CallbackQueue rosProcessQueue
 ROS callbackque that helps process messages. More...
 
std::thread rosProcessQueueThread
 Thread running the rosProcessQueue. More...
 
Eigen::Matrix< msgs::Visual, Eigen::Dynamic, 1 > indicators
 
transport::PublisherPtr indicatorPub
 
transport::NodePtr gazeboNode
 

Detailed Description

Definition at line 29 of file footstep_planner_plugin.h.

Constructor & Destructor Documentation

◆ FootstepPlannerPlugin()

gazebo::FootstepPlannerPlugin::FootstepPlannerPlugin ( )

Definition at line 6 of file footstep_planner_plugin.cpp.

◆ ~FootstepPlannerPlugin()

gazebo::FootstepPlannerPlugin::~FootstepPlannerPlugin ( )
virtual

Definition at line 9 of file footstep_planner_plugin.cpp.

Member Function Documentation

◆ Load()

void gazebo::FootstepPlannerPlugin::Load ( physics::WorldPtr  _world,
sdf::ElementPtr  _sdf 
)
virtual

The Load function is called by Gazebo when the plugin is inserted into simulation.

Parameters
[in]_modelA pointer to the model that the plugin is attached to.
[in]_sdfA pointer to the plugin's SDF element.

Definition at line 37 of file footstep_planner_plugin.cpp.

◆ UpdateFootstepPlan()

void gazebo::FootstepPlannerPlugin::UpdateFootstepPlan ( const geometry_msgs::PoseArray::ConstPtr &  msg)

Definition at line 177 of file footstep_planner_plugin.cpp.

◆ InitRos()

void gazebo::FootstepPlannerPlugin::InitRos ( )

Definition at line 48 of file footstep_planner_plugin.cpp.

◆ InitRosQueueThreads()

void gazebo::FootstepPlannerPlugin::InitRosQueueThreads ( )

Definition at line 19 of file footstep_planner_plugin.cpp.

◆ ProcessQueueThread()

void gazebo::FootstepPlannerPlugin::ProcessQueueThread ( )

Definition at line 27 of file footstep_planner_plugin.cpp.

◆ InitGazebo()

void gazebo::FootstepPlannerPlugin::InitGazebo ( )

Definition at line 66 of file footstep_planner_plugin.cpp.

◆ DeleteVisuals()

void gazebo::FootstepPlannerPlugin::DeleteVisuals ( )

Definition at line 161 of file footstep_planner_plugin.cpp.

◆ SetVisuals()

void gazebo::FootstepPlannerPlugin::SetVisuals ( Eigen::MatrixX3d &  poses)

Definition at line 76 of file footstep_planner_plugin.cpp.

◆ PublishVisuals()

void gazebo::FootstepPlannerPlugin::PublishVisuals ( )

Definition at line 147 of file footstep_planner_plugin.cpp.

Member Data Documentation

◆ world

physics::WorldPtr gazebo::FootstepPlannerPlugin::world
private

Pointer to the world.

Definition at line 59 of file footstep_planner_plugin.h.

◆ rosNode

std::unique_ptr<ros::NodeHandle> gazebo::FootstepPlannerPlugin::rosNode
private

Node used for ROS transport.

Definition at line 62 of file footstep_planner_plugin.h.

◆ footstepPlannerSub

ros::Subscriber gazebo::FootstepPlannerPlugin::footstepPlannerSub
private

Definition at line 64 of file footstep_planner_plugin.h.

◆ rosProcessQueue

ros::CallbackQueue gazebo::FootstepPlannerPlugin::rosProcessQueue
private

ROS callbackque that helps process messages.

Definition at line 67 of file footstep_planner_plugin.h.

◆ rosProcessQueueThread

std::thread gazebo::FootstepPlannerPlugin::rosProcessQueueThread
private

Thread running the rosProcessQueue.

Definition at line 70 of file footstep_planner_plugin.h.

◆ indicators

Eigen::Matrix<msgs::Visual, Eigen::Dynamic, 1> gazebo::FootstepPlannerPlugin::indicators
private

Definition at line 72 of file footstep_planner_plugin.h.

◆ indicatorPub

transport::PublisherPtr gazebo::FootstepPlannerPlugin::indicatorPub
private

Definition at line 74 of file footstep_planner_plugin.h.

◆ gazeboNode

transport::NodePtr gazebo::FootstepPlannerPlugin::gazeboNode
private

Definition at line 76 of file footstep_planner_plugin.h.


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