3 #include <boost/algorithm/string.hpp> 4 #include <geometry_msgs/PointStamped.h> 36 const char* xml =
"<value><array><data><value>/sonar</value></data></array></value>";
38 std::string topics_ns;
41 nh.
param(
"ns", topics_ns, std::string());
42 nh.
param(
"topics", topic_names, topic_names);
45 std::string sensor_type_name;
46 nh.
param(
"input_sensor_type", sensor_type_name, std::string(
"ALL"));
52 boost::to_upper(sensor_type_name);
53 ROS_INFO(
"%s: %s as input_sensor_type given",
name_.c_str(), sensor_type_name.c_str());
55 if (sensor_type_name ==
"VARIABLE")
57 else if (sensor_type_name ==
"FIXED")
58 input_sensor_type =
FIXED;
59 else if (sensor_type_name ==
"ALL")
60 input_sensor_type =
ALL;
63 ROS_ERROR(
"%s: Invalid input sensor type: %s",
name_.c_str(), sensor_type_name.c_str());
69 ROS_ERROR(
"Invalid topic names list: it must be a non-empty list of strings");
73 if (topic_names.
size() < 1)
76 ROS_WARN(
"Empty topic names list: range sensor layer will have no effect on costmap");
80 for (
int i = 0; i < topic_names.
size(); i++)
84 ROS_WARN(
"Invalid topic names list: element %d is not a string, so it will be ignored", i);
88 std::string topic_name(topics_ns);
89 if ((topic_name.size() > 0) && (topic_name.at(topic_name.size() - 1) !=
'/'))
91 topic_name +=
static_cast<std::string
>(topic_names[i]);
95 else if (input_sensor_type ==
FIXED)
97 else if (input_sensor_type ==
ALL)
102 "%s: Invalid input sensor type: %s. Did you make a new type and forgot to choose the subscriber for it?",
103 name_.c_str(), sensor_type_name.c_str());
108 ROS_INFO(
"RangeSensorLayer: subscribed to topic %s",
range_subs_.back().getTopic().c_str());
112 dsrv_ =
new dynamic_reconfigure::Server<range_sensor_layer::RangeSensorLayerConfig>(nh);
113 dynamic_reconfigure::Server<range_sensor_layer::RangeSensorLayerConfig>::CallbackType cb =
115 dsrv_->setCallback(cb);
130 return 1 - (1 +
tanh(2 * (phi -
phi_v_))) / 2;
135 double ta =
tan(angle);
141 *dx = copysign(*dx,
cos(angle));
151 if (phi >= 0.0 && phi < r - 2 * delta * r)
152 return (1 - lbda) * (0.5);
153 else if (phi < r - delta * r)
154 return lbda * 0.5 *
pow((phi - (r - 2 * delta * r)) / (delta * r), 2) + (1 - lbda) * .5;
155 else if (phi < r + delta * r)
157 double J = (r - phi) / (delta * r);
158 return lbda * ((1 - (0.5) *
pow(J, 2)) - 0.5) + 0.5;
189 std::list<sensor_msgs::Range> range_msgs_buffer_copy;
196 for (std::list<sensor_msgs::Range>::iterator range_msgs_it = range_msgs_buffer_copy.begin();
197 range_msgs_it != range_msgs_buffer_copy.end(); range_msgs_it++)
205 if (range_message.min_range == range_message.max_range)
213 if (!std::isinf(range_message.range))
216 "Fixed distance ranger (min_range == max_range) in frame %s sent invalid value. " 217 "Only -Inf (== object detected) and Inf (== no object detected) are valid.",
218 range_message.header.frame_id.c_str());
222 bool clear_sensor_cone =
false;
224 if (range_message.range > 0)
229 clear_sensor_cone =
true;
232 range_message.range = range_message.min_range;
239 if (range_message.range < range_message.min_range || range_message.range > range_message.max_range)
242 bool clear_sensor_cone =
false;
245 clear_sensor_cone =
true;
254 geometry_msgs::PointStamped in, out;
255 in.header.stamp = range_message.header.stamp;
256 in.header.frame_id = range_message.header.frame_id;
262 in.header.stamp.toSec());
268 double ox = out.point.x, oy = out.point.y;
270 in.point.x = range_message.range;
274 double tx = out.point.x, ty = out.point.y;
277 double dx = tx - ox, dy = ty - oy, theta =
atan2(dy, dx),
d =
sqrt(dx * dx + dy * dy);
280 int bx0, by0, bx1, by1;
284 int Ox, Oy, Ax, Ay, Bx, By;
306 bx0 = std::min(bx0, Ax);
307 bx1 = std::max(bx1, Ax);
308 by0 = std::min(by0, Ay);
309 by1 = std::max(by1, Ay);
317 bx0 = std::min(bx0, Bx);
318 bx1 = std::max(bx1, Bx);
319 by0 = std::min(by0, By);
320 by1 = std::max(by1, By);
324 bx0 = std::max(0, bx0);
325 by0 = std::max(0, by0);
326 bx1 = std::min(static_cast<int>(
size_x_), bx1);
327 by1 = std::min(static_cast<int>(
size_y_), by1);
329 for (
unsigned int x = bx0; x <= (
unsigned int)bx1; x++)
331 for (
unsigned int y = by0; y <= (
unsigned int)by1; y++)
333 bool update_xy_cell =
true;
342 int w0 =
orient2d(Ax, Ay, Bx, By, x, y);
343 int w1 =
orient2d(Bx, By, Ox, Oy, x, y);
344 int w2 =
orient2d(Ox, Oy, Ax, Ay, x, y);
348 update_xy_cell = w0 >= bcciath && w1 >= bcciath && w2 >= bcciath;
355 update_cell(ox, oy, theta, range_message.range, wx, wy, clear_sensor_cone);
368 std::map<std::pair<unsigned int, unsigned int>,
double>::iterator it_map;
373 if (it_map->second < removal_time)
386 double dx = nx - ox, dy = ny - oy;
387 double theta =
atan2(dy, dx) - ot;
389 double phi =
sqrt(dx * dx + dy * dy);
394 double prob_occ = sensor * prior;
395 double prob_not = (1 - sensor) * (1 - prior);
396 double new_prob = prob_occ / (prob_occ + prob_not);
398 ROS_DEBUG(
"%f %f | %f %f = %f", dx, dy, theta, phi, sensor);
399 ROS_DEBUG(
"%f | %f %f | %f", prior, prob_occ, prob_not, new_prob);
400 unsigned char c =
to_cost(new_prob);
405 std::pair<unsigned int, unsigned int> coordinate_pair(x, y);
414 std::map<std::pair<unsigned int, unsigned int>,
double>::iterator it_clear;
430 double* min_x,
double* min_y,
double* max_x,
double* max_y)
437 *min_x = std::min(*min_x,
min_x_);
438 *min_y = std::min(*min_y,
min_y_);
439 *max_x = std::max(*max_x,
max_x_);
440 *max_y = std::max(*max_y,
max_y_);
456 "while expected at least every %.2f seconds.",
468 unsigned char* master_array = master_grid.
getCharMap();
472 for (
int j = min_j; j < max_j; j++)
474 unsigned int it = j * span + min_i;
475 for (
int i = min_i; i < max_i; i++)
478 unsigned char current;
484 else if (prob > mark)
486 else if (prob < clear)
494 unsigned char old_cost = master_array[it];
496 if (old_cost == NO_INFORMATION || old_cost < current)
497 master_array[it] = current;
508 ROS_DEBUG(
"Reseting range sensor layer...");
double getSizeInMetersX() const
void get_deltas(double angle, double *dx, double *dy)
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
unsigned int getSizeInCellsX() const
LayeredCostmap * layered_costmap_
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
virtual void onInitialize()
double no_readings_timeout_
void processFixedRangeMsg(sensor_msgs::Range &range_message)
void processRangeMsg(sensor_msgs::Range &range_message)
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
void reconfigureCB(range_sensor_layer::RangeSensorLayerConfig &config, uint32_t level)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void bufferIncomingRangeMsg(const sensor_msgs::RangeConstPtr &range_message)
void processVariableRangeMsg(sensor_msgs::Range &range_message)
std::string getGlobalFrameID() const
bool clear_on_max_reading_
static const unsigned char FREE_SPACE
boost::mutex range_message_mutex_
double getSizeInMetersY() const
std::vector< ros::Subscriber > range_subs_
double gamma(double theta)
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
INLINE Rall1d< T, V, S > tanh(const Rall1d< T, V, S > &arg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Type const & getType() const
boost::function< void(sensor_msgs::Range &range_message)> processRangeMessageFunc_
unsigned char * getCharMap() const
double sensor_model(double r, double phi, double theta)
#define ROS_WARN_THROTTLE(period,...)
dynamic_reconfigure::Server< range_sensor_layer::RangeSensorLayerConfig > * dsrv_
std::map< std::pair< unsigned int, unsigned int >, double > marked_point_history_
#define ROS_ERROR_THROTTLE(period,...)
void update_cell(double ox, double oy, double ot, double r, double nx, double ny, bool clear)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
unsigned int buffered_readings_
double transform_tolerance_
virtual void deactivate()
std::string global_frame_
unsigned char default_value_
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
int orient2d(int Ax, int Ay, int Bx, int By, int Cx, int Cy)
unsigned char to_cost(double p)
void removeOutdatedReadings()
static const unsigned char LETHAL_OBSTACLE
static const unsigned char NO_INFORMATION
ros::Time last_reading_time_
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
virtual void updateOrigin(double new_origin_x, double new_origin_y)
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
std::list< sensor_msgs::Range > range_msgs_buffer_
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
float area(int x1, int y1, int x2, int y2, int x3, int y3)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
unsigned char getCost(unsigned int mx, unsigned int my) const
double to_prob(unsigned char c)