TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
travesim::ros_side::VisionReceiver Class Reference

Class to receive Gazebo published messages. More...

#include "vision_receiver.hpp"

Collaboration diagram for travesim::ros_side::VisionReceiver:

Public Member Functions

 VisionReceiver ()
 Construct a new Vision Receiver object. More...
 
bool receive (gazebo_msgs::ModelStates::ConstPtr *msg)
 Get last received message. More...
 

Private Member Functions

void receive_callback (const gazebo_msgs::ModelStates::ConstPtr &msg)
 Callback function for Gazebo subscriber. More...
 

Private Attributes

gazebo_msgs::ModelStates::ConstPtr world_state
 Cache to save the world state. More...
 
ros::Subscriber subscriber
 Subscriber for Gazebo model_states topic. More...
 
bool received_message
 Flag to indicate if a message was recieved. More...
 

Detailed Description

Class to receive Gazebo published messages.

Definition at line 25 of file vision_receiver.hpp.

Constructor & Destructor Documentation

◆ VisionReceiver()

travesim::ros_side::VisionReceiver::VisionReceiver ( )

Construct a new Vision Receiver object.

Note
Must be called after ros::init()!

Definition at line 18 of file vision_receiver.cpp.

18  {
19  this->received_message = false;
20 
21  ros::NodeHandle _nh;
22  this->subscriber = _nh.subscribe("/gazebo/model_states", 2, &VisionReceiver::receive_callback, this);
23 }
void receive_callback(const gazebo_msgs::ModelStates::ConstPtr &msg)
Callback function for Gazebo subscriber.
ros::Subscriber subscriber
Subscriber for Gazebo model_states topic.
bool received_message
Flag to indicate if a message was recieved.

References receive_callback(), received_message, and subscriber.

Here is the call graph for this function:

Member Function Documentation

◆ receive()

bool travesim::ros_side::VisionReceiver::receive ( gazebo_msgs::ModelStates::ConstPtr *  msg)

Get last received message.

Parameters
msgPointer where to store the message
Returns
true if a new message was received, false otherwise

Definition at line 25 of file vision_receiver.cpp.

25  {
26  if (this->received_message) {
27  *msg = this->world_state;
28  this->received_message = false;
29 
30  return true;
31  }
32 
33  return false;
34 }
gazebo_msgs::ModelStates::ConstPtr world_state
Cache to save the world state.
bool received_message
Flag to indicate if a message was recieved.

References received_message, and world_state.

Here is the caller graph for this function:

◆ receive_callback()

void travesim::ros_side::VisionReceiver::receive_callback ( const gazebo_msgs::ModelStates::ConstPtr &  msg)
private

Callback function for Gazebo subscriber.

Parameters
msgReceived message

Definition at line 36 of file vision_receiver.cpp.

36  {
37  this->received_message = true;
38  this->world_state = msg;
39 }
gazebo_msgs::ModelStates::ConstPtr world_state
Cache to save the world state.
bool received_message
Flag to indicate if a message was recieved.

References received_message, and world_state.

Here is the caller graph for this function:

Member Data Documentation

◆ received_message

bool travesim::ros_side::VisionReceiver::received_message
private

Flag to indicate if a message was recieved.

Definition at line 40 of file vision_receiver.hpp.

◆ subscriber

ros::Subscriber travesim::ros_side::VisionReceiver::subscriber
private

Subscriber for Gazebo model_states topic.

Definition at line 35 of file vision_receiver.hpp.

◆ world_state

gazebo_msgs::ModelStates::ConstPtr travesim::ros_side::VisionReceiver::world_state
private

Cache to save the world state.

Definition at line 30 of file vision_receiver.hpp.


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