|
| 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 |
0 commit comments