GazeboZoneSpawner.cpp 6.06 KB
Newer Older
Johannes Mey's avatar
Johannes Mey committed
1
2
3
4
5
6
7
8
/*! \file GazeboZoneSpawner.cpp

    \author Johannes Mey
    \date 31.03.20
*/

#include "GazeboZoneSpawner.h"

9
#include <sdf/sdf.hh>  // for sdf model parsing
Johannes Mey's avatar
Johannes Mey committed
10
11
12
13
14
#include <gazebo_msgs/SpawnModel.h> // service definition for spawning things in gazebo
#include <ros/ros.h>
#include <ros/package.h>
#include <tf/tf.h>

15
void GazeboZoneSpawner::spawnVisualPrimitive(const std::string &name, shape_msgs::SolidPrimitive shape, geometry_msgs::Pose pose, std_msgs::ColorRGBA color) {
Johannes Mey's avatar
Johannes Mey committed
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
  if (shape.type != shape.BOX) {
    ROS_ERROR_STREAM("Safety-zone could not be created due to wrong shape-type");
    return;
  }

  sdf::SDFPtr sdf(new sdf::SDF());
  sdf::init(sdf);

  auto sdfFileName = ros::package::getPath(ROS_PACKAGE_NAME) + "/models/box.sdf";
  auto materialFileName = "file://" + ros::package::getPath(ROS_PACKAGE_NAME) + "/models/box.material";

  assert(sdf::readFile(sdfFileName, sdf));

  auto visualElement = sdf->Root()->GetElement("model")->GetElement("link")->GetElement("visual");
  auto materialUriElement = visualElement->GetElement("material")->GetElement("script")->GetElement("uri");
  auto poseElement = visualElement->GetElement("pose");
  auto sizeElement = visualElement->GetElement("geometry")->GetElement("box")->GetElement("size");

  materialUriElement->Set(materialFileName);

  tf::Quaternion rot;
  rot.setValue(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w);
  double roll, pitch, yaw;
  tf::Matrix3x3(rot).getRPY(roll, pitch, yaw);

  std::ostringstream poseStream;
  poseStream << pose.position.x << " " << pose.position.y << " " << pose.position.z << " "
             << roll << " " << pitch << " " << yaw;
  poseElement->Set(poseStream.str());

  ROS_INFO_STREAM("Set pose in SDF file to '" << poseElement->GetValue()->GetAsString() << "'.");

  std::ostringstream sizeStream;
  sizeStream << shape.dimensions[0] << " " << shape.dimensions[1] << " " << shape.dimensions[2];
  sizeElement->Set(sizeStream.str());

  ROS_INFO_STREAM("Set size in SDF file to '" << sizeElement->GetValue()->GetAsString() << "'.");

  ros::NodeHandle n;
  ros::ServiceClient client = n.serviceClient<gazebo_msgs::SpawnModel>("/gazebo/spawn_sdf_model");
  gazebo_msgs::SpawnModel srv;
  srv.request.robot_namespace = "box space";
  // srv.request.initial_pose = pose; // not required here
  srv.request.model_name = std::string("box") + poseStream.str() + sizeStream.str();
  srv.request.model_xml = sdf->ToString();
  // srv.request.reference_frame = ; // if left empty, world is used
  if (client.call(srv)) {
    if (srv.response.success) {
      ROS_INFO_STREAM("Spawned box '" << srv.request.model_name << "'. " << srv.response.status_message);
    } else {
      ROS_ERROR_STREAM("Failed to spawn box '" << srv.request.model_name << "'. " << srv.response.status_message);
    }
  } else {
    ROS_ERROR("Failed to call service '/gazebo/spawn_sdf_model'");
  }
}
Johannes Mey's avatar
Johannes Mey committed
72

73
void GazeboZoneSpawner::spawnPrimitive(const std::string &name, shape_msgs::SolidPrimitive shape, geometry_msgs::Pose pose, std_msgs::ColorRGBA, double mass, bool is_static) {
Johannes Mey's avatar
Johannes Mey committed
74
75
76
77
78
79
80
81
  if (shape.type != shape.BOX) {
    ROS_ERROR_STREAM("Safety-zone could not be created due to wrong shape-type");
    return;
  }

  sdf::SDFPtr sdf(new sdf::SDF());
  sdf::init(sdf);

82
  auto sdfFileName = ros::package::getPath(ROS_PACKAGE_NAME) + "/models/physical_box.sdf";
Johannes Mey's avatar
Johannes Mey committed
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
  auto materialFileName = "file://" + ros::package::getPath(ROS_PACKAGE_NAME) + "/models/box.material";

  assert(sdf::readFile(sdfFileName, sdf));

  auto modelElement = sdf->Root()->GetElement("model");
  auto linkElement = modelElement->GetElement("link");
  auto poseElement = linkElement->GetElement("pose");

  auto visualElement = linkElement->GetElement("visual");
  auto visualMaterialUriElement = visualElement->GetElement("material")->GetElement("script")->GetElement("uri");
  auto visualSizeElement = visualElement->GetElement("geometry")->GetElement("box")->GetElement("size");

  auto collisionElement = linkElement->GetElement("collision");
  auto collisionSizeElement = collisionElement->GetElement("geometry")->GetElement("box")->GetElement("size");

  tf::Quaternion rot;
  rot.setValue(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w);
  double roll, pitch, yaw;
  tf::Matrix3x3(rot).getRPY(roll, pitch, yaw);

  std::ostringstream poseStream;
  poseStream << pose.position.x << " " << pose.position.y << " " << pose.position.z << " "
             << roll << " " << pitch << " " << yaw;
  poseElement->Set(poseStream.str());

  // set the element to static
  modelElement->GetElement("static")->Set(is_static);

  double sx = shape.dimensions[0];
  double sy = shape.dimensions[1];
  double sz = shape.dimensions[2];

  // set the size both for visual and collision objects
  std::ostringstream sizeStream;
  sizeStream << sx << " " << sy << " " << sz;
  visualSizeElement->Set(sizeStream.str());
  collisionSizeElement->Set(sizeStream.str());

  // set inertia matrix
  auto inertialElement = sdf->Root()->GetElement("model")->GetElement("link")->GetElement("inertial");
  inertialElement->GetElement("mass")->Set(mass);
  inertialElement->GetElement("inertia")->GetElement("ixx")->Set(0.083 * mass * sy*sy + sz*sz);
  inertialElement->GetElement("inertia")->GetElement("iyy")->Set(0.083 * mass * sx*sx + sz*sz);
  inertialElement->GetElement("inertia")->GetElement("izz")->Set(0.083 * mass * sx*sx + sy*sy);

  ros::NodeHandle n;
  ros::ServiceClient client = n.serviceClient<gazebo_msgs::SpawnModel>("/gazebo/spawn_sdf_model");
  gazebo_msgs::SpawnModel srv;
  srv.request.robot_namespace = "box space";
  // srv.request.initial_pose = pose; // not required here
  srv.request.model_name = name;
  srv.request.model_xml = sdf->ToString();
  // srv.request.reference_frame = ; // if left empty, world is used
  if (client.call(srv)) {
    if (srv.response.success) {
      ROS_INFO_STREAM("Spawned box '" << srv.request.model_name << "'. " << srv.response.status_message);
    } else {
      ROS_ERROR_STREAM("Failed to spawn box '" << srv.request.model_name << "'. " << srv.response.status_message);
    }
  } else {
    ROS_ERROR("Failed to call service '/gazebo/spawn_sdf_model'");
  }
145
}