cnoid_ros_utils
Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | List of all members
CnoidRosUtils::PosePublisherItem Class Reference

Plugin item to publish topics and broadcast TF of pose and velocity of the model. More...

#include <PosePublisherItem.h>

Inheritance diagram for CnoidRosUtils::PosePublisherItem:
Inheritance graph
[legend]
Collaboration diagram for CnoidRosUtils::PosePublisherItem:
Collaboration graph
[legend]

Public Member Functions

 PosePublisherItem ()
 
 PosePublisherItem (const PosePublisherItem &org)
 
 ~PosePublisherItem ()
 

Static Public Member Functions

static void initialize (cnoid::ExtensionManager *ext)
 

Static Public Attributes

static bool initialized_ = false
 

Protected Member Functions

virtual cnoid::Item * doDuplicate () const override
 
virtual void doPutProperties (cnoid::PutPropertyFunction &putProperty) override
 
virtual bool store (cnoid::Archive &archive) override
 
virtual bool restore (const cnoid::Archive &archive) override
 
void setup ()
 
bool start ()
 
void stop ()
 
void onPostDynamics ()
 
int getPubSkip () const
 

Protected Attributes

cnoid::WorldItemPtr world_
 
cnoid::SimulatorItemPtr sim_
 
std::set< std::string > hooked_sims_
 
int post_dynamics_func_id_ = -1
 
cnoid::BodyItem * body_item_
 
std::string link_name_ = ""
 
bool output_tf_ = false
 
std::shared_ptr< ros::NodeHandle > nh_
 
std::string frame_id_ = ""
 
std::string pose_topic_name_ = ""
 
std::string vel_topic_name_ = ""
 
std::string tf_child_frame_id_ = ""
 
double pub_rate_ = 30.0
 
ros::Publisher pose_pub_
 
ros::Publisher vel_pub_
 
std::shared_ptr< tf2_ros::TransformBroadcaster > tf_br_
 
int sim_cnt_ = 0
 
int pub_skip_ = 0
 

Detailed Description

Plugin item to publish topics and broadcast TF of pose and velocity of the model.

Properties

Definition at line 30 of file PosePublisherItem.h.

Constructor & Destructor Documentation

◆ PosePublisherItem() [1/2]

PosePublisherItem::PosePublisherItem ( )

Definition at line 35 of file PosePublisherItem.cpp.

◆ PosePublisherItem() [2/2]

PosePublisherItem::PosePublisherItem ( const PosePublisherItem org)

Definition at line 40 of file PosePublisherItem.cpp.

◆ ~PosePublisherItem()

PosePublisherItem::~PosePublisherItem ( )

Definition at line 48 of file PosePublisherItem.cpp.

Member Function Documentation

◆ doDuplicate()

cnoid::Item * PosePublisherItem::doDuplicate ( ) const
overrideprotectedvirtual

Definition at line 53 of file PosePublisherItem.cpp.

◆ doPutProperties()

void PosePublisherItem::doPutProperties ( cnoid::PutPropertyFunction &  putProperty)
overrideprotectedvirtual

Definition at line 58 of file PosePublisherItem.cpp.

◆ getPubSkip()

int PosePublisherItem::getPubSkip ( ) const
protected

Definition at line 253 of file PosePublisherItem.cpp.

◆ initialize()

void PosePublisherItem::initialize ( cnoid::ExtensionManager *  ext)
static

Definition at line 18 of file PosePublisherItem.cpp.

◆ onPostDynamics()

void PosePublisherItem::onPostDynamics ( )
protected

Definition at line 183 of file PosePublisherItem.cpp.

◆ restore()

bool PosePublisherItem::restore ( const cnoid::Archive &  archive)
overrideprotectedvirtual

Definition at line 90 of file PosePublisherItem.cpp.

◆ setup()

void PosePublisherItem::setup ( )
protected

Definition at line 103 of file PosePublisherItem.cpp.

◆ start()

bool PosePublisherItem::start ( )
protected

Definition at line 126 of file PosePublisherItem.cpp.

◆ stop()

void PosePublisherItem::stop ( )
protected

Definition at line 173 of file PosePublisherItem.cpp.

◆ store()

bool PosePublisherItem::store ( cnoid::Archive &  archive)
overrideprotectedvirtual

Definition at line 77 of file PosePublisherItem.cpp.

Member Data Documentation

◆ body_item_

cnoid::BodyItem* CnoidRosUtils::PosePublisherItem::body_item_
protected

Definition at line 71 of file PosePublisherItem.h.

◆ frame_id_

std::string CnoidRosUtils::PosePublisherItem::frame_id_ = ""
protected

Definition at line 78 of file PosePublisherItem.h.

◆ hooked_sims_

std::set<std::string> CnoidRosUtils::PosePublisherItem::hooked_sims_
protected

Definition at line 67 of file PosePublisherItem.h.

◆ initialized_

bool CnoidRosUtils::PosePublisherItem::initialized_ = false
inlinestatic

Definition at line 35 of file PosePublisherItem.h.

◆ link_name_

std::string CnoidRosUtils::PosePublisherItem::link_name_ = ""
protected

Definition at line 73 of file PosePublisherItem.h.

◆ nh_

std::shared_ptr<ros::NodeHandle> CnoidRosUtils::PosePublisherItem::nh_
protected

Definition at line 77 of file PosePublisherItem.h.

◆ output_tf_

bool CnoidRosUtils::PosePublisherItem::output_tf_ = false
protected

Definition at line 75 of file PosePublisherItem.h.

◆ pose_pub_

ros::Publisher CnoidRosUtils::PosePublisherItem::pose_pub_
protected

Definition at line 83 of file PosePublisherItem.h.

◆ pose_topic_name_

std::string CnoidRosUtils::PosePublisherItem::pose_topic_name_ = ""
protected

Definition at line 79 of file PosePublisherItem.h.

◆ post_dynamics_func_id_

int CnoidRosUtils::PosePublisherItem::post_dynamics_func_id_ = -1
protected

Definition at line 69 of file PosePublisherItem.h.

◆ pub_rate_

double CnoidRosUtils::PosePublisherItem::pub_rate_ = 30.0
protected

Definition at line 82 of file PosePublisherItem.h.

◆ pub_skip_

int CnoidRosUtils::PosePublisherItem::pub_skip_ = 0
protected

Definition at line 88 of file PosePublisherItem.h.

◆ sim_

cnoid::SimulatorItemPtr CnoidRosUtils::PosePublisherItem::sim_
protected

Definition at line 65 of file PosePublisherItem.h.

◆ sim_cnt_

int CnoidRosUtils::PosePublisherItem::sim_cnt_ = 0
protected

Definition at line 87 of file PosePublisherItem.h.

◆ tf_br_

std::shared_ptr<tf2_ros::TransformBroadcaster> CnoidRosUtils::PosePublisherItem::tf_br_
protected

Definition at line 85 of file PosePublisherItem.h.

◆ tf_child_frame_id_

std::string CnoidRosUtils::PosePublisherItem::tf_child_frame_id_ = ""
protected

Definition at line 81 of file PosePublisherItem.h.

◆ vel_pub_

ros::Publisher CnoidRosUtils::PosePublisherItem::vel_pub_
protected

Definition at line 84 of file PosePublisherItem.h.

◆ vel_topic_name_

std::string CnoidRosUtils::PosePublisherItem::vel_topic_name_ = ""
protected

Definition at line 80 of file PosePublisherItem.h.

◆ world_

cnoid::WorldItemPtr CnoidRosUtils::PosePublisherItem::world_
protected

Definition at line 64 of file PosePublisherItem.h.


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