00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/tilt_laser_listener.h"
00037 #include <laser_assembler/AssembleScans2.h>
00038 #include <pcl_conversions/pcl_conversions.h>
00039 #include <jsk_topic_tools/time_accumulator.h>
00040
00041 namespace jsk_pcl_ros
00042 {
00043 StampedJointAngle::StampedJointAngle(const std_msgs::Header& header_arg, const double& value):
00044 header(header_arg), value_(value)
00045 {
00046
00047 }
00048
00049 void TiltLaserListener::onInit()
00050 {
00051 DiagnosticNodelet::onInit();
00052 skip_counter_ = 0;
00053 if (pnh_->hasParam("joint_name")) {
00054 pnh_->getParam("joint_name", joint_name_);
00055 }
00056 else {
00057 NODELET_ERROR("no ~joint_state is specified");
00058 return;
00059 }
00060 pnh_->getParam("twist_frame_id", twist_frame_id_);
00061 pnh_->param("overwrap_angle", overwrap_angle_, 0.0);
00062 std::string laser_type;
00063 bool subscribe_joint = true;
00064 pnh_->param("clear_assembled_scans", clear_assembled_scans_, false);
00065 pnh_->param("skip_number", skip_number_, 1);
00066 pnh_->param("laser_type", laser_type, std::string("tilt_half_down"));
00067 pnh_->param("max_queue_size", max_queue_size_, 100);
00068 pnh_->param("publish_rate", publish_rate_, 1.0);
00069 if (laser_type == "tilt_half_up") {
00070 laser_type_ = TILT_HALF_UP;
00071 }
00072 else if (laser_type == "tilt_half_down") {
00073 laser_type_ = TILT_HALF_DOWN;
00074 }
00075 else if (laser_type == "tilt") {
00076 laser_type_ = TILT;
00077 }
00078 else if (laser_type == "infinite_spindle") {
00079 laser_type_ = INFINITE_SPINDLE;
00080 }
00081 else if (laser_type == "infinite_spindle_half") {
00082 laser_type_ = INFINITE_SPINDLE_HALF;
00083 }
00084 else if (laser_type == "periodic") {
00085 laser_type_ = PERIODIC;
00086 periodic_timer_ = pnh_->createTimer(ros::Duration(1/publish_rate_), &TiltLaserListener::timerCallback, this);
00087 subscribe_joint = false;
00088 }
00089 else {
00090 NODELET_ERROR("unknown ~laser_type: %s", laser_type.c_str());
00091 return;
00092 }
00093 pnh_->param("not_use_laser_assembler_service", not_use_laser_assembler_service_, false);
00094 pnh_->param("use_laser_assembler", use_laser_assembler_, false);
00095 if (use_laser_assembler_) {
00096 if (not_use_laser_assembler_service_) {
00097 sub_cloud_
00098 = pnh_->subscribe("input/cloud", max_queue_size_, &TiltLaserListener::cloudCallback, this);
00099 }
00100 else {
00101 assemble_cloud_srv_
00102 = pnh_->serviceClient<laser_assembler::AssembleScans2>("assemble_scans2");
00103 }
00104 cloud_pub_
00105 = pnh_->advertise<sensor_msgs::PointCloud2>("output_cloud", 1);
00106 }
00107 twist_pub_ = pnh_->advertise<geometry_msgs::TwistStamped>("output_velocity", 1);
00108 prev_angle_ = 0;
00109 prev_velocity_ = 0;
00110 start_time_ = ros::Time::now();
00111 clear_cache_service_ = pnh_->advertiseService(
00112 "clear_cache", &TiltLaserListener::clearCacheCallback,
00113 this);
00114 trigger_pub_ = advertise<jsk_recognition_msgs::TimeRange>(*pnh_, "output", 1);
00115 double vital_rate;
00116 pnh_->param("vital_rate", vital_rate, 1.0);
00117 cloud_vital_checker_.reset(
00118 new jsk_topic_tools::VitalChecker(1 / vital_rate));
00119 if(subscribe_joint) {
00120 sub_ = pnh_->subscribe("input", max_queue_size_, &TiltLaserListener::jointCallback, this);
00121 }
00122
00123 onInitPostProcess();
00124 }
00125
00126 void TiltLaserListener::timerCallback(const ros::TimerEvent& e)
00127 {
00128 boost::mutex::scoped_lock lock(mutex_);
00129 vital_checker_->poke();
00130 publishTimeRange(e.current_real, e.last_real, e.current_real);
00131 start_time_ = e.current_real;
00132 }
00133
00134 void TiltLaserListener::subscribe()
00135 {
00136
00137 }
00138
00139 void TiltLaserListener::unsubscribe()
00140 {
00141
00142 }
00143
00144 void TiltLaserListener::updateDiagnostic(
00145 diagnostic_updater::DiagnosticStatusWrapper &stat)
00146 {
00147 boost::mutex::scoped_lock lock(cloud_mutex_);
00148 if (vital_checker_->isAlive()) {
00149 if (not_use_laser_assembler_service_ &&
00150 use_laser_assembler_) {
00151 if (cloud_vital_checker_->isAlive()) {
00152 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00153 getName() + " running");
00154 }
00155 else {
00156 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00157 "~input/cloud is not activate");
00158 }
00159 stat.add("scan queue", cloud_buffer_.size());
00160 }
00161 else {
00162 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00163 getName() + " running");
00164 }
00165
00166 }
00167 else {
00168 jsk_topic_tools::addDiagnosticErrorSummary(
00169 name_, vital_checker_, stat);
00170 }
00171 }
00172
00173 void TiltLaserListener::cloudCallback(
00174 const sensor_msgs::PointCloud2::ConstPtr& msg)
00175 {
00176 boost::mutex::scoped_lock lock(cloud_mutex_);
00177 cloud_vital_checker_->poke();
00178 cloud_buffer_.push_back(msg);
00179 }
00180
00181 bool TiltLaserListener::clearCacheCallback(
00182 std_srvs::Empty::Request& req,
00183 std_srvs::Empty::Response& res)
00184 {
00185 boost::mutex::scoped_lock lock(mutex_);
00186 buffer_.clear();
00187 return true;
00188 }
00189
00190 void TiltLaserListener::getPointCloudFromLocalBuffer(
00191 const std::vector<sensor_msgs::PointCloud2::ConstPtr>& target_clouds,
00192 sensor_msgs::PointCloud2& output_cloud)
00193 {
00194 if (target_clouds.size() > 0) {
00195 output_cloud.fields = target_clouds[0]->fields;
00196 output_cloud.is_bigendian = target_clouds[0]->is_bigendian;
00197 output_cloud.is_dense = true;
00198 output_cloud.point_step = target_clouds[0]->point_step;
00199 size_t point_num = 0;
00200 size_t data_num = 0;
00201 for (size_t i = 0; i < target_clouds.size(); i++) {
00202 data_num += target_clouds[i]->row_step;
00203 point_num += target_clouds[i]->width * target_clouds[i]->height;
00204 }
00205 output_cloud.data.reserve(data_num);
00206 for (size_t i = 0; i < target_clouds.size(); i++) {
00207 std::copy(target_clouds[i]->data.begin(),
00208 target_clouds[i]->data.end(),
00209 std::back_inserter(output_cloud.data));
00210 }
00211 output_cloud.header.frame_id = target_clouds[0]->header.frame_id;
00212 output_cloud.width = point_num;
00213 output_cloud.height = 1;
00214 output_cloud.row_step = data_num;
00215 }
00216 else {
00217 NODELET_WARN("target_clouds size is 0");
00218 }
00219 }
00220
00221 void TiltLaserListener::publishTimeRange(
00222 const ros::Time& stamp,
00223 const ros::Time& start,
00224 const ros::Time& end)
00225 {
00226 jsk_recognition_msgs::TimeRange range;
00227 range.header.stamp = stamp;
00228 range.start = start;
00229 range.end = end;
00230 trigger_pub_.publish(range);
00231
00232
00233
00234 if (!twist_frame_id_.empty()) {
00235
00236 if (buffer_.size() >= 2) {
00237
00238
00239 StampedJointAngle::Ptr latest = buffer_[buffer_.size() - 1];
00240 StampedJointAngle::Ptr last_second = buffer_[buffer_.size() - 2];
00241 double value_diff = latest->getValue() - last_second->getValue();
00242 double time_diff = (latest->header.stamp - last_second->header.stamp).toSec();
00243 double velocity = value_diff / time_diff;
00244 geometry_msgs::TwistStamped twist;
00245 twist.header.frame_id = twist_frame_id_;
00246 twist.header.stamp = latest->header.stamp;
00247 if (laser_type_ == INFINITE_SPINDLE_HALF ||
00248 laser_type_ == INFINITE_SPINDLE) {
00249 twist.twist.angular.x = velocity;
00250 }
00251 else {
00252 twist.twist.angular.y = velocity;
00253 }
00254 twist_pub_.publish(twist);
00255 }
00256 }
00257
00258 if (use_laser_assembler_) {
00259 if (skip_counter_++ % skip_number_ == 0) {
00260 laser_assembler::AssembleScans2 srv;
00261 srv.request.begin = start;
00262 srv.request.end = end;
00263 try {
00264 if (!not_use_laser_assembler_service_) {
00265 if (assemble_cloud_srv_.call(srv)) {
00266 sensor_msgs::PointCloud2 output_cloud = srv.response.cloud;
00267 output_cloud.header.stamp = stamp;
00268 cloud_pub_.publish(output_cloud);
00269 }
00270 else {
00271 NODELET_ERROR("Failed to call assemble cloud service");
00272 }
00273 }
00274 else {
00275
00276 std::vector<sensor_msgs::PointCloud2::ConstPtr> target_clouds;
00277 {
00278 boost::mutex::scoped_lock lock(cloud_mutex_);
00279 if (cloud_buffer_.size() == 0) {
00280 return;
00281 }
00282 for (size_t i = 0; i < cloud_buffer_.size(); i++) {
00283 ros::Time the_stamp = cloud_buffer_[i]->header.stamp;
00284 if (the_stamp > start && the_stamp < end) {
00285 target_clouds.push_back(cloud_buffer_[i]);
00286 }
00287 }
00288 if (clear_assembled_scans_) {
00289 cloud_buffer_.removeBefore(end);
00290 }
00291 else {
00292 cloud_buffer_.removeBefore(start);
00293 }
00294 }
00295 sensor_msgs::PointCloud2 output_cloud;
00296 getPointCloudFromLocalBuffer(target_clouds, output_cloud);
00297 output_cloud.header.stamp = stamp;
00298 cloud_pub_.publish(output_cloud);
00299 }
00300 }
00301 catch (...) {
00302 NODELET_ERROR("Exception in calling assemble cloud service");
00303 }
00304 }
00305 }
00306 }
00307
00308 void TiltLaserListener::processTiltHalfUp(
00309 const ros::Time& stamp, const double& joint_angle)
00310 {
00311 double velocity = joint_angle - prev_angle_;
00312 if (velocity > 0 && prev_velocity_ <= 0) {
00313 start_time_ = stamp;
00314 }
00315 else if (velocity < 0 && prev_velocity_ >= 0) {
00316 publishTimeRange(stamp, start_time_, stamp);
00317 }
00318 prev_angle_ = joint_angle;
00319 prev_velocity_ = velocity;
00320 }
00321
00322 void TiltLaserListener::processTiltHalfDown(
00323 const ros::Time& stamp, const double& joint_angle)
00324 {
00325 double velocity = joint_angle - prev_angle_;
00326 if (velocity < 0 && prev_velocity_ >= 0) {
00327 start_time_ = stamp;
00328 }
00329 else if (velocity > 0 && prev_velocity_ <= 0) {
00330 publishTimeRange(stamp, start_time_, stamp);
00331 }
00332 prev_angle_ = joint_angle;
00333 prev_velocity_ = velocity;
00334 }
00335
00336 void TiltLaserListener::processTilt(
00337 const ros::Time& stamp, const double& joint_angle)
00338 {
00339
00340 if (buffer_.size() > 3) {
00341 double direction = buffer_[buffer_.size() - 1]->getValue() - joint_angle;
00342 int change_count = 0;
00343 for (size_t i = buffer_.size() - 1; i > 0; i--) {
00344 double current_direction = buffer_[i-1]->getValue() - buffer_[i]->getValue();
00345 if (direction * current_direction < 0) {
00346 ++change_count;
00347 }
00348 if (change_count == 2) {
00349 ros::Time start_time = buffer_[i]->header.stamp;
00350 publishTimeRange(stamp, start_time, stamp);
00351 if (clear_assembled_scans_) {
00352 buffer_.removeBefore(stamp);
00353 }
00354 else {
00355 buffer_.removeBefore(buffer_[i-1]->header.stamp);
00356 }
00357 break;
00358 }
00359 direction = current_direction;
00360 }
00361 }
00362 std_msgs::Header header;
00363 header.stamp = stamp;
00364 StampedJointAngle::Ptr j(new StampedJointAngle(header, joint_angle));
00365 if (buffer_.size() > 0 && buffer_[buffer_.size() - 1]->getValue() == joint_angle) {
00366
00367 }
00368 else {
00369 buffer_.push_back(j);
00370 }
00371 }
00372
00373 void TiltLaserListener::processInfiniteSpindle(
00374 const ros::Time& stamp, const double& joint_angle, const double& velocity,
00375 const double& threshold)
00376 {
00377 if (velocity == 0) {
00378 return;
00379 }
00380 if (buffer_.size() > 3) {
00381 bool jumped = false;
00382 for (size_t i = buffer_.size() - 1; i > 0; i--) {
00383
00384 if (!jumped) {
00385 double direction = fmod(buffer_[i-1]->getValue(), 2.0 * M_PI) - fmod(buffer_[i]->getValue(), 2.0 * M_PI);
00386 if (direction * velocity > 0) {
00387 jumped = true;
00388 }
00389 }
00390 else {
00391 if (velocity > 0) {
00392 if (fmod(buffer_[i-1]->getValue(), 2.0 * M_PI) < fmod(threshold - overwrap_angle_, 2.0 * M_PI)) {
00393 publishTimeRange(stamp, buffer_[i-1]->header.stamp, stamp);
00394 if (clear_assembled_scans_) {
00395 buffer_.removeBefore(stamp);
00396 }
00397 else {
00398 buffer_.removeBefore(buffer_[i-1]->header.stamp);
00399 }
00400 break;
00401 }
00402 }
00403 else if (velocity < 0) {
00404 if (fmod(buffer_[i-1]->getValue(), 2.0 * M_PI) > fmod(threshold + overwrap_angle_, 2.0 * M_PI)) {
00405 publishTimeRange(stamp, buffer_[i-1]->header.stamp, stamp);
00406 if (clear_assembled_scans_) {
00407 buffer_.removeBefore(stamp);
00408 }
00409 else {
00410 buffer_.removeBefore(buffer_[i-1]->header.stamp);
00411 }
00412 break;
00413 }
00414 }
00415 }
00416
00417 }
00418 }
00419 std_msgs::Header header;
00420 header.stamp = stamp;
00421 StampedJointAngle::Ptr j(new StampedJointAngle(header, joint_angle));
00422 buffer_.push_back(j);
00423 }
00424
00425 void TiltLaserListener::jointCallback(
00426 const sensor_msgs::JointState::ConstPtr& msg)
00427 {
00428 boost::mutex::scoped_lock lock(mutex_);
00429 for (size_t i = 0; i < msg->name.size(); i++) {
00430 std::string name = msg->name[i];
00431 if (name == joint_name_) {
00432 vital_checker_->poke();
00433 if (laser_type_ == TILT_HALF_UP) {
00434 processTiltHalfUp(msg->header.stamp, msg->position[i]);
00435 }
00436 else if (laser_type_ == TILT_HALF_DOWN) {
00437 processTiltHalfDown(msg->header.stamp, msg->position[i]);
00438 }
00439 else if (laser_type_ == TILT) {
00440 processTilt(msg->header.stamp, msg->position[i]);
00441 }
00442 else if (laser_type_ == INFINITE_SPINDLE) {
00443 processInfiniteSpindle(msg->header.stamp,
00444 msg->position[i],
00445 msg->velocity[i],
00446 msg->position[i]);
00447 }
00448 else if (laser_type_ == INFINITE_SPINDLE_HALF) {
00449 processInfiniteSpindle(msg->header.stamp,
00450 fmod(msg->position[i], M_PI),
00451 msg->velocity[i],
00452 fmod(msg->position[i], M_PI));
00453 }
00454 break;
00455 }
00456 }
00457 }
00458 }
00459
00460 #include <pluginlib/class_list_macros.h>
00461 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::TiltLaserListener, nodelet::Nodelet);