TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
replacer_sender.hpp
Go to the documentation of this file.
1 /**
2  * @file replacer_sender.hpp
3  * @author Felipe Gomes de Melo <felipe.gomes@thunderatz.org>
4  * @brief
5  * @date 04/2021
6  *
7  * @copyright MIT License - Copyright (c) 2021 ThundeRatz
8  *
9  */
10 
11 #ifndef __REPLACER_SENDER_H__
12 #define __REPLACER_SENDER_H__
13 
14 #include <ros/ros.h>
15 #include <gazebo_msgs/SetModelState.h>
16 
17 namespace travesim {
18 namespace ros_side {
19 /**
20  * @brief All possible commands to send to Gazebo
21  *
22  * @see send_command
23  */
29 };
30 
31 /**
32  * @brief Helper type to set the states of multiple entites at once
33  *
34  */
35 typedef std::vector<gazebo_msgs::ModelState> state_vector_t;
36 
38  private:
39  ros::NodeHandlePtr _nh;
40 
41  ros::ServiceClient gz_service;
42 
43  public:
44  /**
45  * @brief Construct a new Replacer Sender object
46  *
47  */
49 
50  /**
51  * @brief Set state of multiple entities
52  *
53  * @param model_states Vector of states to be set
54  *
55  * @note The affected entity is infered from the model_name of each ModelState
56  *
57  * @return true If sucessfull
58  * @return false If any error occured
59  */
60  bool set_models_state(state_vector_t* model_states);
61 
62  /**
63  * @brief Set the state of one entity
64  *
65  * @param model_state ModelState to be set
66  *
67  * @note The affected entity is infered from the model_name of the ModelState
68  *
69  * @return true If sucessfull
70  * @return false If any error occured
71  */
72  bool set_model_state(gazebo_msgs::ModelState model_state);
73 
74  /**
75  * @brief Send command to gazebo
76  *
77  * @param command
78  * @return true If sucessfull
79  * @return false If any error occured
80  */
81  bool send_command(simulation_command_t command);
82 
83  /**
84  * @brief Attempts to reconnect gz_service ServiceClient if connection dropped
85  *
86  */
88 };
89 } // namespace ros_side
90 } // namespace travesim
91 
92 #endif // __REPLACER_SENDER_H__
void reconnect_service_client()
Attempts to reconnect gz_service ServiceClient if connection dropped.
bool set_model_state(gazebo_msgs::ModelState model_state)
Set the state of one entity.
bool send_command(simulation_command_t command)
Send command to gazebo.
bool set_models_state(state_vector_t *model_states)
Set state of multiple entities.
std::vector< gazebo_msgs::ModelState > state_vector_t
Helper type to set the states of multiple entites at once.
ReplacerSender()
Construct a new Replacer Sender object.
simulation_command_t
All possible commands to send to Gazebo.