35 #define BOOST_PARAMETER_MAX_ARITY 7 37 #include <laser_assembler/AssembleScans2.h> 44 header(header_arg), value_(value)
51 DiagnosticNodelet::onInit();
53 if (pnh_->hasParam(
"joint_name")) {
54 pnh_->getParam(
"joint_name", joint_name_);
60 pnh_->getParam(
"twist_frame_id", twist_frame_id_);
61 pnh_->param(
"overwrap_angle", overwrap_angle_, 0.0);
62 std::string laser_type;
63 bool subscribe_joint =
true;
64 pnh_->param(
"clear_assembled_scans", clear_assembled_scans_,
false);
65 pnh_->param(
"skip_number", skip_number_, 1);
66 pnh_->param(
"laser_type", laser_type, std::string(
"tilt_half_down"));
67 pnh_->param(
"max_queue_size", max_queue_size_, 100);
68 pnh_->param(
"publish_rate", publish_rate_, 1.0);
69 if (laser_type ==
"tilt_half_up") {
70 laser_type_ = TILT_HALF_UP;
72 else if (laser_type ==
"tilt_half_down") {
73 laser_type_ = TILT_HALF_DOWN;
75 else if (laser_type ==
"tilt") {
78 else if (laser_type ==
"infinite_spindle") {
79 laser_type_ = INFINITE_SPINDLE;
81 else if (laser_type ==
"infinite_spindle_half") {
82 laser_type_ = INFINITE_SPINDLE_HALF;
84 else if (laser_type ==
"periodic") {
85 laser_type_ = PERIODIC;
87 subscribe_joint =
false;
93 pnh_->param(
"not_use_laser_assembler_service", not_use_laser_assembler_service_,
false);
94 pnh_->param(
"use_laser_assembler", use_laser_assembler_,
false);
96 pnh_->param(
"vital_rate", vital_rate, 1.0);
97 cloud_vital_checker_.reset(
99 if (use_laser_assembler_) {
100 if (not_use_laser_assembler_service_) {
106 = pnh_->serviceClient<laser_assembler::AssembleScans2>(
"assemble_scans2");
109 = pnh_->advertise<sensor_msgs::PointCloud2>(
"output_cloud", 1);
111 twist_pub_ = pnh_->advertise<geometry_msgs::TwistStamped>(
"output_velocity", 1);
115 clear_cache_service_ = pnh_->advertiseService(
118 trigger_pub_ = advertise<jsk_recognition_msgs::TimeRange>(*pnh_,
"output", 1);
119 if(subscribe_joint) {
129 vital_checker_->poke();
147 boost::mutex::scoped_lock
lock(cloud_mutex_);
148 if (vital_checker_->isAlive()) {
149 if (not_use_laser_assembler_service_ &&
150 use_laser_assembler_) {
151 if (cloud_vital_checker_->isAlive()) {
152 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
156 stat.
summary(diagnostic_error_level_,
157 "~input/cloud is not activate");
159 stat.
add(
"scan queue", cloud_buffer_.size());
162 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
169 name_, vital_checker_, stat, diagnostic_error_level_);
174 const sensor_msgs::PointCloud2::ConstPtr&
msg)
176 boost::mutex::scoped_lock
lock(cloud_mutex_);
177 cloud_vital_checker_->poke();
178 cloud_buffer_.push_back(msg);
182 std_srvs::Empty::Request&
req,
183 std_srvs::Empty::Response&
res)
191 const std::vector<sensor_msgs::PointCloud2::ConstPtr>& target_clouds,
192 sensor_msgs::PointCloud2& output_cloud)
194 if (target_clouds.size() > 0) {
195 output_cloud.fields = target_clouds[0]->fields;
196 output_cloud.is_bigendian = target_clouds[0]->is_bigendian;
197 output_cloud.is_dense =
true;
198 output_cloud.point_step = target_clouds[0]->point_step;
199 size_t point_num = 0;
201 for (
size_t i = 0; i < target_clouds.size(); i++) {
202 data_num += target_clouds[i]->row_step;
203 point_num += target_clouds[i]->width * target_clouds[i]->height;
205 output_cloud.data.reserve(data_num);
206 for (
size_t i = 0; i < target_clouds.size(); i++) {
207 std::copy(target_clouds[i]->
data.begin(),
208 target_clouds[i]->data.end(),
209 std::back_inserter(output_cloud.data));
211 output_cloud.header.frame_id = target_clouds[0]->header.frame_id;
212 output_cloud.width = point_num;
213 output_cloud.height = 1;
214 output_cloud.row_step = data_num;
226 jsk_recognition_msgs::TimeRange range;
227 range.header.stamp =
stamp;
230 trigger_pub_.publish(range);
234 if (!twist_frame_id_.empty()) {
236 if (buffer_.size() >= 2) {
241 double value_diff = latest->getValue() - last_second->getValue();
242 double time_diff = (latest->header.stamp - last_second->header.stamp).toSec();
243 double velocity = value_diff / time_diff;
244 geometry_msgs::TwistStamped twist;
245 twist.header.frame_id = twist_frame_id_;
246 twist.header.stamp = latest->header.stamp;
247 if (laser_type_ == INFINITE_SPINDLE_HALF ||
248 laser_type_ == INFINITE_SPINDLE) {
249 twist.twist.angular.x = velocity;
252 twist.twist.angular.y = velocity;
254 twist_pub_.publish(twist);
258 if (use_laser_assembler_) {
259 if (skip_counter_++ % skip_number_ == 0) {
260 laser_assembler::AssembleScans2
srv;
261 srv.request.begin = start;
262 srv.request.end = end;
264 if (!not_use_laser_assembler_service_) {
265 if (assemble_cloud_srv_.call(srv)) {
266 sensor_msgs::PointCloud2 output_cloud = srv.response.cloud;
267 output_cloud.header.stamp =
stamp;
268 cloud_pub_.publish(output_cloud);
276 std::vector<sensor_msgs::PointCloud2::ConstPtr> target_clouds;
278 boost::mutex::scoped_lock
lock(cloud_mutex_);
279 if (cloud_buffer_.size() == 0) {
282 for (
size_t i = 0; i < cloud_buffer_.size(); i++) {
283 ros::Time the_stamp = cloud_buffer_[i]->header.stamp;
284 if (the_stamp > start && the_stamp < end) {
285 target_clouds.push_back(cloud_buffer_[i]);
288 if (clear_assembled_scans_) {
289 cloud_buffer_.removeBefore(end);
292 cloud_buffer_.removeBefore(start);
295 sensor_msgs::PointCloud2 output_cloud;
296 getPointCloudFromLocalBuffer(target_clouds, output_cloud);
297 output_cloud.header.stamp =
stamp;
298 cloud_pub_.publish(output_cloud);
302 NODELET_ERROR(
"Exception in calling assemble cloud service");
311 double velocity = joint_angle - prev_angle_;
312 if (velocity > 0 && prev_velocity_ <= 0) {
315 else if (velocity < 0 && prev_velocity_ >= 0) {
316 publishTimeRange(stamp, start_time_, stamp);
318 prev_angle_ = joint_angle;
319 prev_velocity_ = velocity;
325 double velocity = joint_angle - prev_angle_;
326 if (velocity < 0 && prev_velocity_ >= 0) {
329 else if (velocity > 0 && prev_velocity_ <= 0) {
330 publishTimeRange(stamp, start_time_, stamp);
332 prev_angle_ = joint_angle;
333 prev_velocity_ = velocity;
340 if (buffer_.size() > 3) {
341 double direction = buffer_[buffer_.size() - 1]->getValue() - joint_angle;
342 int change_count = 0;
343 for (
size_t i = buffer_.size() - 1; i > 0; i--) {
344 double current_direction = buffer_[i-1]->getValue() - buffer_[i]->getValue();
345 if (direction * current_direction < 0) {
348 if (change_count == 2) {
349 ros::Time start_time = buffer_[i]->header.stamp;
350 publishTimeRange(stamp, start_time, stamp);
351 if (clear_assembled_scans_) {
352 buffer_.removeBefore(stamp);
355 buffer_.removeBefore(buffer_[i-1]->
header.stamp);
359 direction = current_direction;
363 header.stamp =
stamp;
365 if (buffer_.size() > 0 && buffer_[buffer_.size() - 1]->getValue() == joint_angle) {
369 buffer_.push_back(j);
374 const ros::Time&
stamp,
const double& joint_angle,
const double& velocity,
375 const double& threshold)
380 if (buffer_.size() > 3) {
382 for (
size_t i = buffer_.size() - 1; i > 0; i--) {
386 if (direction * velocity > 0) {
392 if (fmod(buffer_[i-1]->
getValue(), 2.0 *
M_PI) < fmod(threshold - overwrap_angle_, 2.0 *
M_PI)) {
393 publishTimeRange(stamp, buffer_[i-1]->
header.stamp, stamp);
394 if (clear_assembled_scans_) {
395 buffer_.removeBefore(stamp);
398 buffer_.removeBefore(buffer_[i-1]->
header.stamp);
403 else if (velocity < 0) {
404 if (fmod(buffer_[i-1]->
getValue(), 2.0 *
M_PI) > fmod(threshold + overwrap_angle_, 2.0 *
M_PI)) {
405 publishTimeRange(stamp, buffer_[i-1]->
header.stamp, stamp);
406 if (clear_assembled_scans_) {
407 buffer_.removeBefore(stamp);
410 buffer_.removeBefore(buffer_[i-1]->
header.stamp);
420 header.stamp =
stamp;
422 buffer_.push_back(j);
426 const sensor_msgs::JointState::ConstPtr&
msg)
429 for (
size_t i = 0; i < msg->name.size(); i++) {
430 std::string name = msg->name[i];
431 if (name == joint_name_) {
432 vital_checker_->poke();
433 if(msg->position.size() <= i) {
434 ROS_WARN(
"size of position (%zu) is smaller than joint(%s) position(%zu)",
435 msg->position.size(), name.c_str(), i);
438 if (laser_type_ == TILT_HALF_UP) {
439 processTiltHalfUp(msg->header.stamp, msg->position[i]);
441 else if (laser_type_ == TILT_HALF_DOWN) {
442 processTiltHalfDown(msg->header.stamp, msg->position[i]);
444 else if (laser_type_ == TILT) {
445 processTilt(msg->header.stamp, msg->position[i]);
447 else if (laser_type_ == INFINITE_SPINDLE) {
448 if(msg->velocity.size() <= i) {
449 ROS_WARN(
"size of velocity (%zu) is smaller than joint(%s) position(%zu)",
450 msg->velocity.size(), name.c_str(), i);
453 processInfiniteSpindle(msg->header.stamp,
458 else if (laser_type_ == INFINITE_SPINDLE_HALF) {
459 if(msg->velocity.size() <= i) {
460 ROS_WARN(
"size of velocity (%zu) is smaller than joint(%s) position(%zu)",
461 msg->velocity.size(), name.c_str(), i);
464 processInfiniteSpindle(msg->header.stamp,
465 fmod(msg->position[i],
M_PI),
467 fmod(msg->position[i],
M_PI));
virtual double getValue()
#define NODELET_ERROR(...)
virtual void processTiltHalfDown(const ros::Time &stamp, const double &value)
virtual void publishTimeRange(const ros::Time &stamp, const ros::Time &start, const ros::Time &end)
#define NODELET_WARN(...)
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
StampedJointAngle(const std_msgs::Header &header_arg, const double &value)
void summary(unsigned char lvl, const std::string s)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::TiltLaserListener, nodelet::Nodelet)
virtual void processInfiniteSpindle(const ros::Time &stamp, const double &joint_angle, const double &velocity, const double &threshold)
std::string getName(void *handle)
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void unsubscribe()
virtual void jointCallback(const sensor_msgs::JointState::ConstPtr &msg)
virtual void getPointCloudFromLocalBuffer(const std::vector< sensor_msgs::PointCloud2::ConstPtr > &target_clouds, sensor_msgs::PointCloud2 &output_cloud)
virtual void processTiltHalfUp(const ros::Time &stamp, const double &value)
virtual void processTilt(const ros::Time &stamp, const double &value)
virtual void timerCallback(const ros::TimerEvent &e)
void add(const std::string &key, const T &val)
virtual bool clearCacheCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)