Skip to content

Commit 27abfbc

Browse files
committed
feat: adds laser plugin
1 parent 7ab6ad0 commit 27abfbc

File tree

10 files changed

+722
-0
lines changed

10 files changed

+722
-0
lines changed

mujoco_ros/CHANGELOG.md

+1
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ If a number above 1 is used, multithreading is enabled. MuJoCo will then use the
77
The default is `min(#available_threads - 1, 4)`.
88
* Added profiling of plugin load and callback execution times. For each callback an EMA with sensitivity of 1000 steps is computed. In case a plugin has lower frequency than simulation step size, the callback should set `skip_ema_ = true` when skipping computations.
99
Loading and reset times are reported in the server debug log. All plugin stats can be retrieved by the `get_plugin_stats` service call.
10+
* Added ros laser plugin.
1011

1112
### Fixed
1213
* Added missing call to render callbacks in viewer. While the callbacks were still being run for offscreen rendering, the viewer did not render additional geoms added by plugins.

mujoco_ros_laser/CMakeLists.txt

+69
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,69 @@
1+
cmake_minimum_required(VERSION 3.0.2)
2+
3+
# TODO: Set the actual project name
4+
project(mujoco_ros_laser)
5+
6+
# Optional: change/add more flags
7+
set( CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -Wl,--no-undefined" )
8+
9+
set(CMAKE_CXX_STANDARD 17)
10+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
11+
12+
if(NOT CMAKE_BUILD_TYPE)
13+
message(STATUS "CMAKE_BUILD_TYPE not set. Defaulting to 'Release'.")
14+
set(CMAKE_BUILD_TYPE Release)
15+
endif()
16+
17+
set(CMAKE_CXX_FLAGS_SANITIZE "-fsanitize=address -g -O1 -fno-inline -fno-omit-frame-pointer -fno-optimize-sibling-calls")
18+
19+
find_package(catkin REQUIRED COMPONENTS
20+
roscpp
21+
pluginlib
22+
mujoco_ros
23+
mujoco_ros_sensors
24+
sensor_msgs
25+
)
26+
27+
catkin_package(
28+
CATKIN_DEPENDS
29+
roscpp
30+
pluginlib
31+
mujoco_ros
32+
mujoco_ros_sensors
33+
sensor_msgs
34+
INCLUDE_DIRS
35+
include
36+
LIBRARIES
37+
${PROJECT_NAME}
38+
)
39+
40+
add_library(${PROJECT_NAME}
41+
src/laser.cpp
42+
)
43+
target_include_directories(${PROJECT_NAME} PUBLIC
44+
${PROJECT_SOURCE_DIR}/include
45+
${catkin_INCLUDE_DIRS}
46+
)
47+
48+
target_link_libraries(${PROJECT_NAME}
49+
${catkin_LIBRARIES}
50+
)
51+
52+
install(TARGETS ${PROJECT_NAME}
53+
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
54+
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
55+
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
56+
)
57+
58+
install(DIRECTORY include/${PROJECT_NAME}/
59+
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
60+
)
61+
62+
install(FILES
63+
mujoco_laser_plugin.xml
64+
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
65+
)
66+
67+
install(DIRECTORY launch config assets
68+
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
69+
)

mujoco_ros_laser/README.md

+13
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
# MuJoCo ROS Laser Plugin
2+
3+
Provides a CPU-based Laser sensor, using MuJoCo's `ray_collision` function.
4+
5+
This plugin uses MuJoCo's threadpool, if using more than 1 thread is configured in the server.
6+
7+
## Configuration Example
8+
9+
https://github.com/ubi-agni/mujoco_ros/blob/noetic-devel/mujoco_ros_laser/config/laser_example_config.yaml?plain=1
10+
11+
## License
12+
13+
This repository is licensed under the [BSD License](../mujoco_ros/LICENSE).
+38
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
<mujoco model="Laser Example">
2+
<option timestep="0.001" gravity="0 0 -9.81" cone="elliptic" />
3+
<compiler angle="radian" />
4+
5+
<visual>
6+
<headlight ambient="0.4 0.4 0.4" diffuse="0.4 0.4 0.4" specular="0.0 0.0 0.0" active="1" />
7+
</visual>
8+
9+
<asset>
10+
<texture builtin="checker" height="512" name="texplane" rgb1=".2 .3 .4" rgb2=".1 .15 .2" type="2d" width="512" />
11+
<material name="MatPlane" reflectance="0.5" shininess="0.01" specular="0.1" texrepeat="1 1" texture="texplane" texuniform="true" />
12+
</asset>
13+
14+
<worldbody>
15+
<light pos="0 0 1000" castshadow="false" />
16+
<geom name="ground_plane" type="plane" size="10 10 10" material="MatPlane" rgba="1 1 1 1"/>
17+
18+
<body name="obs0" pos="5. -2.5 0.2" euler="0 0 1.2">
19+
<freejoint />
20+
<geom type="box" size="0.2 0.2 0.2" rgba="1. 0 0. 1." />
21+
</body>
22+
23+
<body name="obs1" pos="7. 0. 0.2">
24+
<freejoint />
25+
<geom type="box" size="0.2 0.2 0.2" rgba="1. 0 0. 1." />
26+
</body>
27+
28+
<body name="obs2" pos="6. 2.5 0.2" euler="0 0 .9">
29+
<freejoint />
30+
<geom type="box" size="0.2 0.2 0.2" rgba="1. 0 0. 1." />
31+
</body>
32+
33+
<body name="laser" pos="0 0 .3">
34+
<geom type="box" size=".2 .2 .3" rgba="0.8 0.8 0.8 0.2" />
35+
<site pos=".21 0 -0.1" name="laser_site" size="0.05" />
36+
</body>
37+
</worldbody>
38+
</mujoco>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
MujocoPlugins:
2+
- type: mujoco_ros_laser/LaserPlugin
3+
sensors:
4+
- site_attached: laser_site
5+
frame_id: scan
6+
visualize: true
7+
update_rate: 10.
8+
min_range: 0.1
9+
max_range: 30.
10+
range_resolution: 0.01
11+
angular_resolution: 0.02
12+
min_angle: -1.57
13+
max_angle: 1.57
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,157 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2023, Bielefeld University
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of Bielefeld University nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
35+
/* Authors: David P. Leins */
36+
37+
#pragma once
38+
39+
#include <mujoco_ros/plugin_utils.h>
40+
#include <mujoco_ros/common_types.h>
41+
#include <mujoco_ros/mujoco_env.h>
42+
43+
#include <mujoco_ros_sensors/mujoco_sensor_handler_plugin.h>
44+
45+
#include <ros/ros.h>
46+
47+
#include <random>
48+
49+
using namespace mujoco_ros;
50+
using namespace mujoco_ros::sensors;
51+
52+
namespace mujoco_ros::sensors::laser {
53+
54+
// Defaults
55+
static bool DEFAULT_VISUALIZE = false;
56+
static double DEFAULT_UPDATE_RATE = 10.;
57+
static double DEFAULT_MIN_RANGE = 0.1;
58+
static double DEFAULT_MAX_RANGE = 30.;
59+
static double DEFAULT_RANGE_RESOLUTION = 0.01;
60+
static double DEFAULT_ANGULAR_RESOLUTION = 0.02;
61+
static double DEFAULT_MIN_ANGLE = -1.57;
62+
static double DEFAULT_MAX_ANGLE = 1.57;
63+
static double DEFAULT_SENSOR_STD = 0.005;
64+
65+
struct LaserConfig : public SensorConfig
66+
{
67+
public:
68+
LaserConfig(const XmlRpc::XmlRpcValue &config, const std::string &frame_id, const std::string &name,
69+
int site_attached); // : SensorConfig(std::move(frame_id)), name(std::move(name)),
70+
// site_attached(site_attached);
71+
LaserConfig(std::string frame_id, std::string name, int site_attached, bool visualize, double update_rate,
72+
double min_range, double max_range, double range_resolution, double angular_resolution, double min_angle,
73+
double max_angle)
74+
: SensorConfig(std::move(frame_id))
75+
, name(std::move(name))
76+
, site_attached(site_attached)
77+
, visualize(visualize)
78+
, update_rate(update_rate)
79+
, min_range(min_range)
80+
, max_range(max_range)
81+
, range_resolution(range_resolution)
82+
, angular_resolution(angular_resolution)
83+
, min_angle(min_angle)
84+
, max_angle(max_angle){};
85+
86+
// Sensor name
87+
std::string name;
88+
// Site in the model to attach the laser to
89+
int site_attached;
90+
// Whether to visualize the laser scan in the simulation
91+
bool visualize;
92+
// The update rate of the laser scan in Hz
93+
double update_rate;
94+
// The minimum range of the laser scan
95+
mjtNum min_range;
96+
// The maximum range of the laser scan
97+
mjtNum max_range;
98+
// The range resolution of the laser scan in meters
99+
double range_resolution;
100+
// The angular resolution of the laser scan in radians
101+
double angular_resolution;
102+
// The minimum and maximum angle of the laser scan in radians
103+
double min_angle;
104+
double max_angle;
105+
106+
uint nrays;
107+
mjtNum *rays;
108+
109+
mjtNum cur_xpos[3];
110+
};
111+
112+
class LaserPlugin : public MujocoPlugin
113+
{
114+
public:
115+
~LaserPlugin() override;
116+
117+
bool load(const mjModel *m, mjData *d) override;
118+
void reset() override;
119+
120+
void renderCallback(const mjModel *model, mjData *data, mjvScene *scene) override;
121+
void lastStageCallback(const mjModel *model, mjData *data) override;
122+
123+
private:
124+
// The env_ptr_ (shared_ptr) in the parent class ensures mjModel and mjData are not destroyed
125+
const mjModel *m_;
126+
mjData *d_;
127+
128+
// Laser sensor configurations
129+
std::vector<LaserConfig> laser_configs_;
130+
// Handle for publishers of laser scan messages
131+
ros::NodeHandle lasers_nh_;
132+
133+
// Last sim time the laser was computed
134+
ros::Time last_update_time_;
135+
136+
// Initialize the laser sensor configuration
137+
bool initSensor(const mjModel *model, const XmlRpc::XmlRpcValue &config);
138+
139+
// Laser computation
140+
void computeLasers(const mjModel *model, mjData *data);
141+
// Multi-threaded computation of laser rays
142+
void computeLasersMultithreaded(const mjModel *model, mjData *data);
143+
144+
// Laser visualization geoms
145+
mjvGeom *laser_geoms_;
146+
// Number of laser geoms
147+
int ngeom_ = 0;
148+
149+
// Whether at least one sensor is to be rendered
150+
bool has_render_data_ = false;
151+
152+
// Random number generator for sensor noise
153+
std::mt19937 rand_generator = std::mt19937(std::random_device{}());
154+
// Normal distribution for sensor noise
155+
std::normal_distribution<double> noise_dist;
156+
};
157+
} // namespace mujoco_ros::sensors::laser
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<arg name="modelfile" default="$(find mujoco_ros_laser)/assets/laser_world.xml" doc="MuJoCo xml file to load. Should define robot model and world." />
4+
<arg name="mujoco_plugin_config" default="$(find mujoco_ros_laser)/config/laser_example_config.yaml" doc="Optionally provide the path to a yaml with plugin configurations to load" />
5+
<arg name="verbose" default="false" />
6+
7+
<env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}] [${logger}] [${node}]: ${message}"/>
8+
<env if="$(arg verbose)" name="ROSCONSOLE_CONFIG_FILE"
9+
value="$(find mujoco_ros)/rosconsole.config"/>
10+
11+
<include file="$(find mujoco_ros)/launch/launch_server.launch" pass_all_args="true">
12+
<arg name="use_sim_time" value="true" />
13+
</include>
14+
</launch>
+10
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
<library path="lib/libmujoco_ros_laser">
2+
<class
3+
name="mujoco_ros_laser/LaserPlugin"
4+
type="mujoco_ros::sensors::laser::LaserPlugin"
5+
base_class_type="mujoco_ros::MujocoPlugin">
6+
<description>
7+
MuJoCo ROS Laser Plugin
8+
</description>
9+
</class>
10+
</library>

mujoco_ros_laser/package.xml

+23
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
<?xml version="1.0"?>
2+
<package format="2">
3+
<name>mujoco_ros_laser</name>
4+
<version>0.9.0</version>
5+
<description>MuJoCo ROS Laser Plugin</description>
6+
7+
8+
<maintainer email="dleins@techfak.uni-bielefeld.de">David Leins</maintainer>
9+
<author>David P. Leins</author>
10+
11+
<license>BSD</license>
12+
13+
<buildtool_depend>catkin</buildtool_depend>
14+
<depend>roscpp</depend>
15+
<depend>pluginlib</depend>
16+
<depend>mujoco_ros</depend>
17+
<depend>mujoco_ros_sensors</depend>
18+
<depend>sensor_msgs</depend>
19+
20+
<export>
21+
<mujoco_ros plugin="${prefix}/mujoco_laser_plugin.xml" />
22+
</export>
23+
</package>

0 commit comments

Comments
 (0)