TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
vision_receiver.hpp
Go to the documentation of this file.
1 /**
2  * @file vision_receiver.hpp
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 #ifndef __VISION_RECEIVER_H__
13 #define __VISION_RECEIVER_H__
14 
15 #include <ros/ros.h>
16 #include <ros/console.h>
17 #include <gazebo_msgs/ModelStates.h>
18 
19 namespace travesim {
20 namespace ros_side {
21 /**
22  * @brief Class to receive Gazebo published messages
23  *
24  */
26  private:
27  /**
28  * @brief Cache to save the world state
29  */
30  gazebo_msgs::ModelStates::ConstPtr world_state;
31 
32  /**
33  * @brief Subscriber for Gazebo model_states topic
34  */
35  ros::Subscriber subscriber;
36 
37  /**
38  * @brief Flag to indicate if a message was recieved
39  */
41 
42  /**
43  * @brief Callback function for Gazebo subscriber
44  *
45  * @param msg Received message
46  */
47  void receive_callback(const gazebo_msgs::ModelStates::ConstPtr& msg);
48 
49  public:
50  /**
51  * @brief Construct a new Vision Receiver object
52  *
53  * @note Must be called after ros::init()!
54  */
56 
57  /**
58  * @brief Get last received message
59  *
60  * @param msg Pointer where to store the message
61  *
62  * @return true if a new message was received, false otherwise
63  */
64  bool receive(gazebo_msgs::ModelStates::ConstPtr* msg);
65 };
66 } // ros_side
67 } // travesim
68 
69 #endif // __VISION_RECEIVER_H__
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.
Class to receive Gazebo published messages.
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.