TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
travesim::ros_side::ReplacerSender Class Reference

#include "replacer_sender.hpp"

Collaboration diagram for travesim::ros_side::ReplacerSender:

Public Member Functions

 ReplacerSender ()
 Construct a new Replacer Sender object. More...
 
bool set_models_state (state_vector_t *model_states)
 Set state of multiple entities. More...
 
bool set_model_state (gazebo_msgs::ModelState model_state)
 Set the state of one entity. More...
 
bool send_command (simulation_command_t command)
 Send command to gazebo. More...
 
void reconnect_service_client ()
 Attempts to reconnect gz_service ServiceClient if connection dropped. More...
 

Private Attributes

ros::NodeHandlePtr _nh
 
ros::ServiceClient gz_service
 

Detailed Description

Definition at line 37 of file replacer_sender.hpp.

Constructor & Destructor Documentation

◆ ReplacerSender()

travesim::ros_side::ReplacerSender::ReplacerSender ( )

Construct a new Replacer Sender object.

Definition at line 23 of file replacer_sender.cpp.

23  {
24  _nh = ros::NodeHandlePtr(new ros::NodeHandle());
26 }
void reconnect_service_client()
Attempts to reconnect gz_service ServiceClient if connection dropped.

References _nh, and reconnect_service_client().

Here is the call graph for this function:

Member Function Documentation

◆ reconnect_service_client()

void travesim::ros_side::ReplacerSender::reconnect_service_client ( )

Attempts to reconnect gz_service ServiceClient if connection dropped.

If the connection dropped, we try to reconnect

Definition at line 28 of file replacer_sender.cpp.

28  {
29  /**
30  * @brief If the connection dropped, we try to reconnect
31  */
32  if (!this->gz_service.isValid()) {
33  this->gz_service = this->_nh->serviceClient<gazebo_msgs::SetModelState>("/gazebo/set_model_state");
34  }
35 }

References _nh, and gz_service.

Here is the caller graph for this function:

◆ send_command()

bool travesim::ros_side::ReplacerSender::send_command ( simulation_command_t  command)

Send command to gazebo.

Parameters
command
Returns
true If sucessfull
false If any error occured

Definition at line 65 of file replacer_sender.cpp.

65  {
66  static std::unordered_map<simulation_command_t, std::string> topics_table({
67  {travesim::ros_side::PAUSE, "/gazebo/pause_physics" },
68  {travesim::ros_side::RESUME, "/gazebo/unpause_physics"},
69  {travesim::ros_side::RESET_WORLD, "/gazebo/reset_world"},
70  {travesim::ros_side::RESET_SIMULATION, "/gazebo/reset_simulation"},
71  });
72 
73  std_srvs::Empty msg;
74 
75  if (topics_table[command] == "") {
76  return false;
77  } else {
78  ros::service::call(topics_table[command], msg);
79  return true;
80  }
81 }

References travesim::ros_side::PAUSE, travesim::ros_side::RESET_SIMULATION, travesim::ros_side::RESET_WORLD, and travesim::ros_side::RESUME.

Here is the caller graph for this function:

◆ set_model_state()

bool travesim::ros_side::ReplacerSender::set_model_state ( gazebo_msgs::ModelState  model_state)

Set the state of one entity.

Parameters
model_stateModelState to be set
Note
The affected entity is infered from the model_name of the ModelState
Returns
true If sucessfull
false If any error occured

Definition at line 37 of file replacer_sender.cpp.

37  {
38  static gazebo_msgs::SetModelStateRequest request;
39  static gazebo_msgs::SetModelStateResponse response;
40 
42  request.model_state = model_state;
43 
44  bool status = this->gz_service.call(request, response);
45 
46  if (!(status && response.success)) {
47  ROS_ERROR_STREAM("Error while calling set_model_state " << model_state);
48  return false;
49  }
50 
51  return true;
52 }
void reconnect_service_client()
Attempts to reconnect gz_service ServiceClient if connection dropped.

References gz_service, and reconnect_service_client().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_models_state()

bool travesim::ros_side::ReplacerSender::set_models_state ( state_vector_t model_states)

Set state of multiple entities.

Parameters
model_statesVector of states to be set
Note
The affected entity is infered from the model_name of each ModelState
Returns
true If sucessfull
false If any error occured

Definition at line 54 of file replacer_sender.cpp.

54  {
55  for (uint32_t i = 0; i < model_states->size(); i++) {
56  if (!this->set_model_state(model_states->at(i))) {
57  ROS_ERROR_STREAM("Error while calling set_team_state at i = " << i);
58  return false;
59  }
60  }
61 
62  return true;
63 }
bool set_model_state(gazebo_msgs::ModelState model_state)
Set the state of one entity.

References set_model_state().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _nh

ros::NodeHandlePtr travesim::ros_side::ReplacerSender::_nh
private

Definition at line 39 of file replacer_sender.hpp.

◆ gz_service

ros::ServiceClient travesim::ros_side::ReplacerSender::gz_service
private

Definition at line 41 of file replacer_sender.hpp.


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