-
Notifications
You must be signed in to change notification settings - Fork 101
/
gazebo_cube_spawner.h
40 lines (30 loc) · 1.11 KB
/
gazebo_cube_spawner.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
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
#ifndef GAZEBO_TEST_TOOLS_GAZEBOCUBESPAWNER
#define GAZEBO_TEST_TOOLS_GAZEBOCUBESPAWNER
#include <ros/ros.h>
namespace gazebo_test_tools {
/**
* Spawns a cube of given size, position and orientation into
* Gazebo.
*
* \author Jennifer Buehler
*/
class GazeboCubeSpawner {
public:
GazeboCubeSpawner(ros::NodeHandle &n);
void spawnCube(const std::string& name, const std::string& frame_id,
float x, float y, float z, float qx, float qy, float qz, float qw,
float w=0.05, float h=0.05, float d=0.05, float mass=0.05);
/**
* \param isCube if true, spawn a cube. If false, spawn cylinder,
* where \e w is the radius and \e h is the height (\e d will be ignored).
*/
void spawnPrimitive(const std::string& name, const bool isCube,
const std::string& frame_id,
float x, float y, float z, float qx, float qy, float qz, float qw,
float w=0.05, float h=0.05, float d=0.05, float mass=0.05);
private:
ros::NodeHandle nh;
ros::ServiceClient spawn_object;
};
} // namespace
#endif // GAZEBO_TEST_TOOLS_GAZEBOCUBESPAWNER