Public Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::LeicaPlugin Class Reference

#include <leica_plugin.h>

Inheritance diagram for gazebo::LeicaPlugin:
Inheritance graph
[legend]

Public Member Functions

void configureScanWindow (const sensor_msgs::RegionOfInterestConstPtr &_msg)
 Configure the scan window from a topic. More...
 
 LeicaPlugin ()
 Construct a new Gazebo ROS Laser object. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load the plugin controller. More...
 
 ~LeicaPlugin ()
 Destroy the Gazebo ROS Laser object. More...
 

Private Member Functions

void callbacksQueueHelperThread ()
 Thread that calls all functions in the callback queue when resources are available. More...
 
void connectToLaser ()
 Register de new laser and connect to its topic. More...
 
void disconnectFromLaser ()
 Unregister the laser. More...
 
void gazeboLoaderThread ()
 Load the sensor controller. More...
 
void gazeboMsgToROSMsg (ConstLaserScanStampedPtr &_msg)
 Tailor the gazebo message to the ROS format. More...
 

Private Attributes

ros::CallbackQueue cb_queue_
 Queue for the callback functions. More...
 
std::condition_variable condition_variable_
 Variable used to wait until the configuration of the scan window has been completed. More...
 
boost::thread deferred_load_thread_
 Object for the sensor controller thread. More...
 
std::string frame_name_
 Stores the name of the root of the reference system tree. More...
 
gazebo::transport::NodePtr gazebo_node_
 Node for gazebo. More...
 
int laser_connect_count_
 A counter to register the number of laser sensors in use. More...
 
gazebo::transport::SubscriberPtr laser_scan_sub_
 Gazebo part of the laser sensor subscriber. More...
 
std::mutex mutex_
 Mutex used so that no laser sensor data is published until the configuration of the scan window has been completed. More...
 
std::string namespace_
 The namespace of the Leica station. More...
 
ros::NodeHandlenh_
 Pointer to the ROS node. More...
 
sensors::GpuRaySensorPtr parent_ray_sensor_
 Pointer to the laser sensor object. More...
 
PubMultiQueue pmq_
 Object for the ROS queue system. More...
 
ros::Publisher pub_
 Publisher for the laser sensor. More...
 
PubQueue< sensor_msgs::LaserScan >::Ptr pub_queue_
 Publisher queue. More...
 
std::thread queue_helper_thread_
 Thread that calls all functions in the callback queue when resources are available. More...
 
sdf::ElementPtr sdf_
 Pointer to the *.sdf file. More...
 
unsigned int seed_
 Seed for the Gaussian noise generator. More...
 
bool start_laser_
 Flag to start the laser after the scan window has been set. More...
 
ros::Subscriber sub_
 Subscriber for the laser sensor. More...
 
std::string tf_prefix_
 tf_prefix_ as the namespace More...
 
std::string topic_name_
 Saves the name of the topic where the laser scanner publishes what it reads. More...
 
physics::WorldPtr world_
 Pointer to the virtual world where the simulation takes place. More...
 
std::string world_name_
 Stores the name of the virtual world where the simulation takes place. More...
 

Detailed Description

Definition at line 56 of file leica_plugin.h.

Constructor & Destructor Documentation

gazebo::LeicaPlugin::LeicaPlugin ( )

Construct a new Gazebo ROS Laser object.

Definition at line 56 of file leica_plugin.cpp.

gazebo::LeicaPlugin::~LeicaPlugin ( )

Destroy the Gazebo ROS Laser object.

Definition at line 62 of file leica_plugin.cpp.

Member Function Documentation

void gazebo::LeicaPlugin::callbacksQueueHelperThread ( )
private

Thread that calls all functions in the callback queue when resources are available.

Definition at line 250 of file leica_plugin.cpp.

void gazebo::LeicaPlugin::configureScanWindow ( const sensor_msgs::RegionOfInterestConstPtr &  _msg)

Configure the scan window from a topic.

Parameters
_msgMessage with the scan window configuration format

Definition at line 218 of file leica_plugin.cpp.

void gazebo::LeicaPlugin::connectToLaser ( )
private

Register de new laser and connect to its topic.

Definition at line 177 of file leica_plugin.cpp.

void gazebo::LeicaPlugin::disconnectFromLaser ( )
private

Unregister the laser.

Definition at line 192 of file leica_plugin.cpp.

void gazebo::LeicaPlugin::gazeboLoaderThread ( )
private

Load the sensor controller.

Definition at line 137 of file leica_plugin.cpp.

void gazebo::LeicaPlugin::gazeboMsgToROSMsg ( ConstLaserScanStampedPtr &  _msg)
private

Tailor the gazebo message to the ROS format.

Parameters
_msgMessage to tailor

Definition at line 199 of file leica_plugin.cpp.

void gazebo::LeicaPlugin::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the plugin controller.

Parameters
_parentPointer to the laser sensor
_sdfPointer to the *.sdf file with the Leica configuration

Definition at line 71 of file leica_plugin.cpp.

Member Data Documentation

ros::CallbackQueue gazebo::LeicaPlugin::cb_queue_
private

Queue for the callback functions.

Definition at line 218 of file leica_plugin.h.

std::condition_variable gazebo::LeicaPlugin::condition_variable_
private

Variable used to wait until the configuration of the scan window has been completed.

Definition at line 182 of file leica_plugin.h.

boost::thread gazebo::LeicaPlugin::deferred_load_thread_
private

Object for the sensor controller thread.

Definition at line 254 of file leica_plugin.h.

std::string gazebo::LeicaPlugin::frame_name_
private

Stores the name of the root of the reference system tree.

Definition at line 158 of file leica_plugin.h.

gazebo::transport::NodePtr gazebo::LeicaPlugin::gazebo_node_
private

Node for gazebo.

Definition at line 224 of file leica_plugin.h.

int gazebo::LeicaPlugin::laser_connect_count_
private

A counter to register the number of laser sensors in use.

Definition at line 134 of file leica_plugin.h.

gazebo::transport::SubscriberPtr gazebo::LeicaPlugin::laser_scan_sub_
private

Gazebo part of the laser sensor subscriber.

Definition at line 230 of file leica_plugin.h.

std::mutex gazebo::LeicaPlugin::mutex_
private

Mutex used so that no laser sensor data is published until the configuration of the scan window has been completed.

Definition at line 176 of file leica_plugin.h.

std::string gazebo::LeicaPlugin::namespace_
private

The namespace of the Leica station.

Definition at line 170 of file leica_plugin.h.

ros::NodeHandle* gazebo::LeicaPlugin::nh_
private

Pointer to the ROS node.

Definition at line 200 of file leica_plugin.h.

sensors::GpuRaySensorPtr gazebo::LeicaPlugin::parent_ray_sensor_
private

Pointer to the laser sensor object.

Definition at line 194 of file leica_plugin.h.

PubMultiQueue gazebo::LeicaPlugin::pmq_
private

Object for the ROS queue system.

Definition at line 242 of file leica_plugin.h.

ros::Publisher gazebo::LeicaPlugin::pub_
private

Publisher for the laser sensor.

Definition at line 206 of file leica_plugin.h.

PubQueue<sensor_msgs::LaserScan>::Ptr gazebo::LeicaPlugin::pub_queue_
private

Publisher queue.

Definition at line 236 of file leica_plugin.h.

std::thread gazebo::LeicaPlugin::queue_helper_thread_
private

Thread that calls all functions in the callback queue when resources are available.

Definition at line 188 of file leica_plugin.h.

sdf::ElementPtr gazebo::LeicaPlugin::sdf_
private

Pointer to the *.sdf file.

Definition at line 248 of file leica_plugin.h.

unsigned int gazebo::LeicaPlugin::seed_
private

Seed for the Gaussian noise generator.

Definition at line 122 of file leica_plugin.h.

bool gazebo::LeicaPlugin::start_laser_
private

Flag to start the laser after the scan window has been set.

Definition at line 128 of file leica_plugin.h.

ros::Subscriber gazebo::LeicaPlugin::sub_
private

Subscriber for the laser sensor.

Definition at line 212 of file leica_plugin.h.

std::string gazebo::LeicaPlugin::tf_prefix_
private

tf_prefix_ as the namespace

Definition at line 164 of file leica_plugin.h.

std::string gazebo::LeicaPlugin::topic_name_
private

Saves the name of the topic where the laser scanner publishes what it reads.

Definition at line 152 of file leica_plugin.h.

physics::WorldPtr gazebo::LeicaPlugin::world_
private

Pointer to the virtual world where the simulation takes place.

Definition at line 146 of file leica_plugin.h.

std::string gazebo::LeicaPlugin::world_name_
private

Stores the name of the virtual world where the simulation takes place.

Definition at line 140 of file leica_plugin.h.


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


leica_gazebo_simulation
Author(s): Ines Lara Sicilia
autogenerated on Mon Feb 22 2021 03:50:48