Skip to content
Snippets Groups Projects
Select Git revision
  • 815a248170b589b82d736278a65d11bfd1ca2d3e
  • noetic/main default protected
  • melodic/main
3 results

GazeboZoneSpawner.h

Blame
  • GazeboZoneSpawner.h 5.09 KiB
    /*! \file GazeboZoneSpawner.cpp
    
        \author Johannes Mey
        \date 31.03.20
    */
    
    #ifndef SIMULATION_UTIL_GAZEBOZONESPAWNER_H
    #define SIMULATION_UTIL_GAZEBOZONESPAWNER_H
    
    
    #include <shape_msgs/SolidPrimitive.h>
    #include <geometry_msgs/Pose.h>
    #include <std_msgs/ColorRGBA.h>
    
    /*!
     * A class for spawning safety zones in the Gazebo simulator.
     */
    class GazeboZoneSpawner {
    
    public:
    
      /**
       * @brief Spawns a purely visual box that ignores physics and is ignored by collision detection.
       *
       * The box is based on a prototype located in the package at `models/box.sdf`:
       * ```xml
       * <?xml version="1.0" ?>
       * <sdf version="1.5">
       *   <model name="box">
       *     <static>true</static>
       *     <link name="link">
       *       <visual name="visual">
       *         <material>
       *           <script>
       *             <uri>box.material</uri>
       *             <name>Gazebo/DarkMagentaTransparent</name>
       *           </script>
       *         </material>
       *         <pose>0 0 0 0 0 0</pose>
       *         <geometry>
       *           <box>
       *             <size>1 1 1</size>
       *           </box>
       *         </geometry>
       *       </visual>
       *     </link>
       *   </model>
       * </sdf>
       * ```
       *
       * Before the box is spawned, its pose and size are adapted to the method parameters.
       *
       * Currently, color of the box is provided in a material file in the package at `models/box.material`. Alternatively,
       * the built-in materials could be used, but due to some bugs in gazebo_ros, the absolute URI would have to be
       * provided, e.g., `/usr/share/gazebo-9/media/materials/scripts/gazebo.material`, which would make the package
       * dependent on particular versions and installation locations. For future extensions, a `color` parameter is
       * provided.
       *
       * @param name The name of the box, which must be unique within gazebo.
       * @param shape The shape of the collision box. Currently, only `BOX` is supported.
       * @param pose The pose of the box. The position of the box is its center.
       * @param color The color of the box. This parameter is currently ignored.
       */
      static void spawnVisualPrimitive(const std::string &name, shape_msgs::SolidPrimitive shape, geometry_msgs::Pose pose, std_msgs::ColorRGBA color = std_msgs::ColorRGBA());
    
      /**
       * @brief Spawns a box with physical properties.
       *
       * The box is based on a prototype located in the package at `models/box.sdf`:
       * ```xml
       * <?xml version="1.0" ?>
       * <sdf version="1.5">
       *   <model name="box">
       *     <static>false</static>
       *     <link name="link">
       *       <pose>2 3 0.5 0 0 0</pose>
       *       <inertial>
       *         <mass>1.0</mass>
       *         <inertia>
       *           <ixx>0.083</ixx>       <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
       *           <ixy>0.0</ixy>         <!-- for a box: ixy = 0 -->
       *           <ixz>0.0</ixz>         <!-- for a box: ixz = 0 -->
       *           <iyy>0.083</iyy>       <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
       *           <iyz>0.0</iyz>         <!-- for a box: iyz = 0 -->
       *           <izz>0.083</izz>       <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
       *         </inertia>
       *       </inertial>
       *       <visual name="visual">
       *         <material>
       *           <script>
       *             <uri>box.material</uri>
       *             <name>Zone/DarkMagentaTransparent</name>
       *           </script>
       *         </material>
       *         <geometry>
       *           <box>
       *             <size>1 1 1</size>
       *           </box>
       *         </geometry>
       *       </visual>
       *       <collision name="collision">
       *         <geometry>
       *           <box>
       *             <size>1 1 1</size>
       *           </box>
       *         </geometry>
       *       </collision>
       *     </link>
       *   </model>
       * </sdf>
       * ```
       *
       * Before the box is spawned, its pose, inertial matrix, mass, and size are adapted to the method parameters.
       *
       * Currently, color of the box is provided in a material file in the package at `models/box.material`. Alternatively,
       * the built-in materials could be used, but due to some bugs in gazebo_ros, the absolute URI would have to be
       * provided, e.g., `/usr/share/gazebo-9/media/materials/scripts/gazebo.material`, which would make the package
       * dependent on particular versions and installation locations. For future extensions, a `color` parameter is
       * provided.
       *
       * @param name The name of the box, which must be unique within gazebo.
       * @param shape The shape of the collision box. Currently, only `BOX` is supported.
       * @param pose The pose of the box. The position of the box is its center.
       * @param color The color of the box. This parameter is currently ignored.
       * @param mass The weight of the box in kg. Irrelevant, if `is_static` is set to true.
       * @param is_static True, if the box should be ignored by physical forces (such as gravity). It is still considered for collisions.
       */
      static void spawnPrimitive(const std::string &name, shape_msgs::SolidPrimitive shape, geometry_msgs::Pose pose, std_msgs::ColorRGBA = std_msgs::ColorRGBA(), double mass = 1.0, bool is_static = false);
    
    };
    
    
    #endif //SIMULATION_UTIL_GAZEBOZONESPAWNER_H