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