44 #include <sensor_msgs/LaserScan.h> 90 const double mo_old_width)
95 - width_factor * fabs(mo.seen_width - mo_old_width));
104 LaserScanArrayInterpreterNodelet::LaserScanArrayInterpreterNodelet()
106 LaserScanInterpreterNodelet::LaserScanInterpreterNodelet()
111 LaserScanArrayInterpreterNode::LaserScanArrayInterpreterNode()
113 LaserScanInterpreterNode::LaserScanInterpreterNode()
138 LaserScanArrayInterpreterNodelet::~LaserScanArrayInterpreterNodelet()
141 LaserScanArrayInterpreterNode::~LaserScanArrayInterpreterNode()
145 LaserScanInterpreterNodelet::~LaserScanInterpreterNodelet()
148 LaserScanInterpreterNode::~LaserScanInterpreterNode()
152 int nr_banks =
banks.size();
153 for (
int i=0; i<nr_banks; ++i)
168 void LaserScanArrayInterpreterNodelet::laserScanArrayCallback(
const find_moving_objects::LaserScanArray::ConstPtr & msg)
171 void LaserScanArrayInterpreterNode::laserScanArrayCallback(
const find_moving_objects::LaserScanArray::ConstPtr & msg)
192 for (
int i=0; i<msg->msgs.size(); ++i)
202 banks[i]->findAndReportMovingObjects();
214 banks[0]->findAndReportMovingObjects();
230 ROS_DEBUG_STREAM(
"LaserScanArray sensor is using frame: " << msg->header.frame_id);
235 const int nr_msgs = msg->msgs.size();
236 if (
banks.size() == 0)
242 banks.resize(nr_msgs);
243 for (
int i=0; i<nr_msgs; ++i)
253 for (
int i=0; i<nr_msgs; ++i)
255 const std::string append_str =
"_" + std::to_string(i);
257 bank_arguments[i].topic_objects_closest_point_markers.append(append_str);
258 bank_arguments[i].topic_objects_velocity_arrows.append(append_str);
259 bank_arguments[i].topic_objects_delta_position_lines.append(append_str);
271 for (
int i=0; i<nr_msgs; ++i)
277 if (
banks.size() == 0)
315 bank_arguments[0].nr_scans_in_bank = nr_scans - ((long) nr_scans) == 0.0 ? nr_scans + 1 : ceil(nr_scans);
330 " (based on " <<
received_messages <<
" msgs during " << elapsed_time <<
" seconds)");
335 " (based on " <<
received_messages <<
" msgs during " << elapsed_time <<
" seconds)");
365 ROS_ERROR(
"Message callback is in an unknown state");
376 void LaserScanArrayInterpreterNodelet::onInit()
378 void LaserScanInterpreterNodelet::onInit()
382 nh = getNodeHandle();
383 nh_priv = getPrivateNodeHandle();
387 void LaserScanArrayInterpreterNode::onInit()
389 void LaserScanInterpreterNode::onInit()
482 tf_filter->registerCallback( boost::bind(
485 &LaserScanArrayInterpreterNodelet::laserScanArrayCallback,
492 &LaserScanArrayInterpreterNode::laserScanArrayCallback,
508 int main (
int argc,
char ** argv)
515 LaserScanArrayInterpreterNode ls_interpreter;
521 LaserScanInterpreterNode ls_interpreter;
double optimize_nr_scans_in_bank
double object_threshold_max_distance
bool publish_objects_velocity_arrows
#define NODELET_INFO_STREAM(...)
const bool default_publish_objects_width_lines
double object_threshold_min_speed
const bool default_publish_objects_closest_points_markers
bool velocity_arrows_use_full_gray_scale
const std::string default_ns_velocity_arrows
bool publish_objects_closest_point_markers
const double default_object_threshold_edge_max_delta_range
const bool default_velocity_arrows_use_fixed_frame
std::string topic_objects_closest_point_markers
std::string delta_position_line_ns
const bool default_publish_objects_delta_position_lines
double object_threshold_bank_tracking_max_delta_distance
BankArgument bank_argument
virtual long init(BankArgument bank_argument, const sensor_msgs::LaserScan *msg)
double max_confidence_for_dt_match
virtual long addMessage(const sensor_msgs::LaserScan *msg)
bool publish_objects_delta_position_lines
message_filters::Subscriber< sensor_msgs::LaserScan > * tf_subscriber
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const double default_base_confidence
bool velocity_arrows_use_sensor_frame
const std::string default_topic_objects_closest_points_markers
int subscribe_buffer_size
const double default_ema_alpha
const std::string default_subscribe_topic
const bool default_publish_ema
const std::string default_topic_objects
const int default_subscribe_buffer_size
const bool default_velocity_arrows_use_full_gray_scale
void laserScanCallback(const sensor_msgs::LaserScan::ConstPtr &msg)
std::string width_line_ns
const int default_nr_scans_in_bank
const bool default_velocity_arrows_use_base_frame
ROSCPP_DECL void spin(Spinner &spinner)
const std::string default_topic_objects_width_lines
const double default_object_threshold_min_speed
double object_threshold_edge_max_delta_range
std::string topic_objects_width_lines
const double default_max_confidence_for_dt_match
std::string velocity_arrow_ns
const std::string default_ns_delta_position_lines
const std::string default_ns_width_lines
const int default_object_threshold_max_delta_width_in_points
const double default_delta_width_confidence_decrease_factor
const std::string default_topic_ema
std::vector< BankArgument > bank_arguments
const double default_optimize_nr_scans_in_bank
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const double default_object_threshold_bank_tracking_max_delta_distance
const double default_object_threshold_min_confidence
const std::string default_fixed_frame
const int default_object_threshold_min_nr_points
int main(int argc, char **argv)
const std::string default_topic_objects_delta_position_lines
std::string topic_objects_velocity_arrows
virtual double calculateConfidence(const find_moving_objects::MovingObject &mo, const find_moving_objects::BankArgument &ba, const double delta_time, const double mo_old_width)
std::string topic_objects_delta_position_lines
const double default_object_threshold_max_distance
#define ROS_DEBUG_STREAM(args)
const bool default_publish_objects
#define NODELET_DEBUG_STREAM(...)
tf2_ros::Buffer * tf_buffer
tf2_ros::TransformListener * tf_listener
tf2_ros::MessageFilter< sensor_msgs::LaserScan > * tf_filter
const std::string default_base_frame
bool velocity_arrows_use_fixed_frame
std::vector< Bank * > banks
const std::string default_map_frame
std::string subscribe_topic
const bool default_velocity_arrows_use_sensor_frame
const int default_publish_buffer_size
#define ROS_INFO_STREAM(args)
int object_threshold_max_delta_width_in_points
int object_threshold_min_nr_points
const bool default_publish_objects_velocity_arrows
bool publish_objects_width_lines
static bool waitForValid()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool velocity_arrows_use_base_frame
std::string topic_objects
std::vector< std::string > tf_filter_target_frames
const std::string default_topic_objects_velocity_arrows
double object_threshold_min_confidence