16 #include <unordered_map> 21 #include <sensor_msgs/Range.h> 24 namespace extra_plugins {
26 class DistanceSensorPlugin;
35 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 data.reserve(ACC_SIZE);
81 data.push_back(range);
85 if (++data_index > ACC_SIZE - 1)
89 float average, variance, sum = 0, sum_ = 0;
95 average = sum / data.size();
99 sum_ += (
d - average) * (
d - average);
101 variance = sum_ / data.size();
116 dist_nh(
"~distance_sensor")
123 dist_nh.param<std::string>(
"base_frame_id", base_frame_id,
"base_link");
126 if (!dist_nh.getParam(
"", map_dict)) {
133 for (
auto &pair : map_dict) {
134 ROS_DEBUG_NAMED(
"distance_sensor",
"DS: initializing mapping for %s", pair.first.c_str());
138 sensor_map[it->sensor_id] = it;
140 ROS_ERROR_NAMED(
"distance_sensor",
"DS: bad config for %s", pair.first.c_str());
158 std::unordered_map<uint8_t, DistanceSensorItem::Ptr>
sensor_map;
162 uint32_t min_distance,
163 uint32_t max_distance,
164 uint32_t current_distance,
165 uint8_t
type, uint8_t
id,
168 mavlink::common::msg::DISTANCE_SENSOR ds;
181 ds.time_boot_ms = time_boot_ms;
182 ds.min_distance = min_distance;
183 ds.max_distance = max_distance;
184 ds.current_distance = current_distance;
201 using mavlink::common::MAV_SENSOR_ORIENTATION;
202 using mavlink::common::MAV_DISTANCE_SENSOR;
204 auto it = sensor_map.find(dist_sen.id);
205 if (it == sensor_map.end()) {
207 "DS: no mapping for sensor id: %d, type: %d, orientation: %d",
208 dist_sen.id, dist_sen.type, dist_sen.orientation);
212 auto sensor = it->second;
213 if (sensor->is_subscriber) {
215 "DS: %s (id %d) is subscriber, but i got sensor data for that id from FCU",
216 sensor->topic_name.c_str(), sensor->sensor_id);
221 if (sensor->orientation >= 0 && dist_sen.orientation != sensor->orientation) {
223 "DS: %s: received sensor data has different orientation (%s) than in config (%s)!",
224 sensor->topic_name.c_str(),
225 utils::to_string_enum<MAV_SENSOR_ORIENTATION>(dist_sen.orientation).c_str(),
226 utils::to_string_enum<MAV_SENSOR_ORIENTATION>(sensor->orientation).c_str());
229 auto range = boost::make_shared<sensor_msgs::Range>();
231 range->header =
m_uas->synchronized_header(sensor->frame_id, dist_sen.time_boot_ms);
233 range->min_range = dist_sen.min_distance * 1
E-2;
234 range->max_range = dist_sen.max_distance * 1
E-2;
235 range->field_of_view = sensor->field_of_view;
237 switch (dist_sen.type) {
240 case enum_value(MAV_DISTANCE_SENSOR::UNKNOWN):
241 range->radiation_type = sensor_msgs::Range::INFRARED;
243 case enum_value(MAV_DISTANCE_SENSOR::ULTRASOUND):
244 range->radiation_type = sensor_msgs::Range::ULTRASOUND;
248 "DS: %s: Wrong/undefined type of sensor (type: %d). Droping!...",
249 sensor->topic_name.c_str(), dist_sen.type);
253 range->range = dist_sen.current_distance * 1
E-2;
255 if (sensor->send_tf) {
259 geometry_msgs::TransformStamped
transform;
261 transform.header =
m_uas->synchronized_header(base_frame_id, dist_sen.time_boot_ms);
262 transform.child_frame_id = sensor->frame_id;
269 m_uas->tf2_broadcaster.sendTransform(transform);
272 sensor->pub.publish(range);
278 using mavlink::common::MAV_DISTANCE_SENSOR;
281 uint8_t covariance_ = 0;
290 if (msg->radiation_type == sensor_msgs::Range::INFRARED)
291 type =
enum_value(MAV_DISTANCE_SENSOR::LASER);
292 else if (msg->radiation_type == sensor_msgs::Range::ULTRASOUND)
293 type =
enum_value(MAV_DISTANCE_SENSOR::ULTRASOUND);
296 msg->header.stamp.toNSec() / 1000000,
297 msg->min_range / 1
E-2,
298 msg->max_range / 1
E-2,
308 auto p = boost::make_shared<DistanceSensorItem>();
309 std::string orientation_str;
318 pnh.
param(
"subscriber", p->is_subscriber,
false);
323 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: `id` not set!", topic_name.c_str());
329 if (!pnh.
getParam(
"orientation", orientation_str))
336 if (!p->is_subscriber) {
339 if (!pnh.
getParam(
"frame_id", p->frame_id)) {
340 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: `frame_id` not set!", topic_name.c_str());
344 if (!pnh.
getParam(
"field_of_view", p->field_of_view)) {
345 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: sensor FOV not set!", topic_name.c_str());
350 if (p->orientation == -1 && !orientation_str.empty()) {
351 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: defined orientation (%s) is not valid!",
352 topic_name.c_str(), orientation_str.c_str());
357 pnh.
param(
"send_tf", p->send_tf,
false);
359 pnh.
param(
"sensor_position/x", p->position.x(), 0.0);
360 pnh.
param(
"sensor_position/y", p->position.y(), 0.0);
361 pnh.
param(
"sensor_position/z", p->position.z(), 0.0);
362 ROS_DEBUG_NAMED(
"sensor_position",
"DS: %s: Sensor position at: %f, %f, %f", topic_name.c_str(),
363 p->position.x(), p->position.y(), p->position.z());
369 if (orientation_str.empty()) {
370 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: orientation not set!", topic_name.c_str());
373 else if (p->orientation == -1) {
374 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: defined orientation (%s) is not valid!", topic_name.c_str(), orientation_str.c_str());
379 pnh.
param(
"covariance", p->covariance, 0);
383 if (!p->is_subscriber)
void range_cb(const sensor_msgs::Range::ConstPtr &msg)
int covariance
in centimeters, current specification
std::shared_ptr< MAVConnInterface const > ConstPtr
float calculate_variance(float range)
#define ROS_WARN_NAMED(name,...)
uint8_t sensor_id
id of the sensor
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
size_t data_index
array index
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
int orientation
check orientation of sensor if != -1
Eigen::Vector3d position
sensor position
DistanceSensorPlugin * owner
static Ptr create_item(DistanceSensorPlugin *owner, std::string topic_name)
Subscriptions get_subscriptions()
std::string frame_id
frame id for send
#define ROS_ERROR_ONCE_NAMED(name,...)
std::unordered_map< uint8_t, DistanceSensorItem::Ptr > sensor_map
Eigen::Quaterniond sensor_orientation_matching(mavlink::common::MAV_SENSOR_ORIENTATION orientation)
#define ROS_DEBUG_NAMED(name,...)
std::atomic< uint8_t > type
bool is_subscriber
this item is a subscriber, else is a publisher
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
#define UAS_FCU(uasobjptr)
PluginBase(const PluginBase &)=delete
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool send_tf
defines if a transform is sent or not
double field_of_view
FOV of the sensor.
int sensor_orientation_from_str(const std::string &sensor_orientation)
static constexpr size_t ACC_SIZE
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_)
bool getParam(const std::string &key, std::string &s) const
void distance_sensor(uint32_t time_boot_ms, uint32_t min_distance, uint32_t max_distance, uint32_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
#define ROS_ERROR_NAMED(name,...)
std::string base_frame_id
void handle_distance_sensor(const mavlink::mavlink_message_t *msg, mavlink::common::msg::DISTANCE_SENSOR &dist_sen)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
boost::shared_ptr< DistanceSensorItem > Ptr
void initialize(UAS &uas_)
std::vector< float > data
array allocation for measurements
constexpr std::underlying_type< _T >::type enum_value(_T e)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW DistanceSensorItem()