TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
gazebo_services.mock.cpp File Reference
#include <ros/ros.h>
#include <ros/console.h>
#include <gazebo_msgs/ModelState.h>
#include <gazebo_msgs/ModelStates.h>
#include <gazebo_msgs/SetModelState.h>
#include <gazebo_msgs/GetModelState.h>
#include "travesim_adapters/data/converter/ros_side.hpp"
#include <iostream>
#include <unordered_map>
Include dependency graph for gazebo_services.mock.cpp:

Go to the source code of this file.

Functions

bool set_model_state (gazebo_msgs::SetModelState::Request &req, gazebo_msgs::SetModelState::Response &res)
 
bool get_model_state (gazebo_msgs::GetModelState::Request &req, gazebo_msgs::GetModelState::Response &res)
 
int main (int argc, char **argv)
 

Variables

std::unordered_map< std::string, gazebo_msgs::ModelState > world_data
 

Detailed Description

Author
Felipe Gomes de Melo felip.nosp@m.e.go.nosp@m.mes@t.nosp@m.hund.nosp@m.eratz.nosp@m..org
Date
04/2021

Definition in file gazebo_services.mock.cpp.

Function Documentation

◆ get_model_state()

bool get_model_state ( gazebo_msgs::GetModelState::Request &  req,
gazebo_msgs::GetModelState::Response &  res 
)

Definition at line 31 of file gazebo_services.mock.cpp.

31  {
32  res.pose = world_data.at(req.model_name).pose;
33  res.twist = world_data.at(req.model_name).twist;
34  res.success = true;
35  return true;
36 }
std::unordered_map< std::string, gazebo_msgs::ModelState > world_data

References world_data.

Here is the caller graph for this function:

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 38 of file gazebo_services.mock.cpp.

38  {
39  ros::init(argc, argv, "gazebo_mock");
40  ros::NodeHandle nh;
41 
42  ros::ServiceServer setter_service = nh.advertiseService("/gazebo/set_model_state", set_model_state);
43  ros::ServiceServer getter_service = nh.advertiseService("/gazebo/get_model_state", get_model_state);
44 
45  ros::Publisher pub = nh.advertise<gazebo_msgs::ModelStates>("/gazebo/model_states", 1, true);
46 
47  gazebo_msgs::ModelStates empty_msg;
48 
49  pub.publish(empty_msg);
50 
51  ros::spin();
52 
53  return 0;
54 }
bool set_model_state(gazebo_msgs::SetModelState::Request &req, gazebo_msgs::SetModelState::Response &res)
bool get_model_state(gazebo_msgs::GetModelState::Request &req, gazebo_msgs::GetModelState::Response &res)

References get_model_state(), and set_model_state().

Here is the call graph for this function:

◆ set_model_state()

bool set_model_state ( gazebo_msgs::SetModelState::Request &  req,
gazebo_msgs::SetModelState::Response &  res 
)

Definition at line 25 of file gazebo_services.mock.cpp.

25  {
26  world_data[req.model_state.model_name] = req.model_state;
27  res.success = true;
28  return true;
29 }
std::unordered_map< std::string, gazebo_msgs::ModelState > world_data

References world_data.

Here is the caller graph for this function:

Variable Documentation

◆ world_data

std::unordered_map<std::string, gazebo_msgs::ModelState> world_data

Definition at line 23 of file gazebo_services.mock.cpp.