TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
vision_receiver.cpp
Go to the documentation of this file.
1 /**
2  * @file vision_receiver.cpp
3  * @author Felipe Gomes de Melo <felipe.gomes@thunderatz.org>
4  * @author Lucas Haug <lucas.haug@thunderatz.org>
5  * @brief ROS vision receiver class definition
6  * @date 04/2021
7  *
8  * @copyright MIT License - Copyright (c) 2021 ThundeRatz
9  *
10  */
11 
12 #include <ros/console.h>
13 #include <gazebo_msgs/ModelStates.h>
15 
16 namespace travesim {
17 namespace ros_side {
19  this->received_message = false;
20 
21  ros::NodeHandle _nh;
22  this->subscriber = _nh.subscribe("/gazebo/model_states", 2, &VisionReceiver::receive_callback, this);
23 }
24 
25 bool VisionReceiver::receive(gazebo_msgs::ModelStates::ConstPtr* msg) {
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 }
35 
36 void VisionReceiver::receive_callback(const gazebo_msgs::ModelStates::ConstPtr& msg) {
37  this->received_message = true;
38  this->world_state = msg;
39 }
40 } // namespace ros_side
41 } // namespace travesim
ROS vision receiver class definition.
void receive_callback(const gazebo_msgs::ModelStates::ConstPtr &msg)
Callback function for Gazebo subscriber.
gazebo_msgs::ModelStates::ConstPtr world_state
Cache to save the world state.
VisionReceiver()
Construct a new Vision Receiver object.
bool receive(gazebo_msgs::ModelStates::ConstPtr *msg)
Get last received message.
ros::Subscriber subscriber
Subscriber for Gazebo model_states topic.
bool received_message
Flag to indicate if a message was recieved.