kobuki_bumper2pc.cpp
Go to the documentation of this file.
00001 
00010 /*****************************************************************************
00011 ** Includes
00012 *****************************************************************************/
00013 
00014 #include <pluginlib/class_list_macros.h>
00015 
00016 #include "kobuki_bumper2pc/kobuki_bumper2pc.hpp"
00017 
00018 namespace kobuki_bumper2pc
00019 {
00020 
00021 void Bumper2PcNodelet::coreSensorCB(const kobuki_msgs::SensorState::ConstPtr& msg)
00022 {
00023   if (pointcloud_pub_.getNumSubscribers() == 0)
00024     return;
00025 
00026   // We publish just one "no events" pc and stop spamming when bumper/cliff conditions disappear
00027   if (! msg->bumper && ! msg->cliff && ! prev_bumper && ! prev_cliff)
00028     return;
00029 
00030   prev_bumper = msg->bumper;
00031   prev_cliff  = msg->cliff;
00032 
00033   // We replicate the sensors order of bumper/cliff event messages: LEFT = 0, CENTER = 1 and RIGHT = 2
00034   if ((msg->bumper & kobuki_msgs::SensorState::BUMPER_LEFT) ||
00035       (msg->cliff  & kobuki_msgs::SensorState::CLIFF_LEFT))
00036   {
00037     memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[0].offset], &p_side_x_, sizeof(float));
00038     memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[1].offset], &p_side_y_, sizeof(float));
00039   }
00040   else
00041   {
00042     memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[0].offset], &P_INF_X, sizeof(float));
00043     memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[1].offset], &P_INF_Y, sizeof(float));
00044   }
00045 
00046   if ((msg->bumper & kobuki_msgs::SensorState::BUMPER_CENTRE) ||
00047       (msg->cliff  & kobuki_msgs::SensorState::CLIFF_CENTRE))
00048   {
00049     memcpy(&pointcloud_.data[1 * pointcloud_.point_step + pointcloud_.fields[0].offset], &pc_radius_, sizeof(float));
00050   }
00051   else
00052   {
00053     memcpy(&pointcloud_.data[1 * pointcloud_.point_step + pointcloud_.fields[0].offset], &P_INF_X, sizeof(float));
00054   }
00055 
00056   if ((msg->bumper & kobuki_msgs::SensorState::BUMPER_RIGHT) ||
00057       (msg->cliff  & kobuki_msgs::SensorState::CLIFF_RIGHT))
00058   {
00059     memcpy(&pointcloud_.data[2 * pointcloud_.point_step + pointcloud_.fields[0].offset], &p_side_x_, sizeof(float));
00060     memcpy(&pointcloud_.data[2 * pointcloud_.point_step + pointcloud_.fields[1].offset], &n_side_y_, sizeof(float));
00061   }
00062   else
00063   {
00064     memcpy(&pointcloud_.data[2 * pointcloud_.point_step + pointcloud_.fields[0].offset], &P_INF_X, sizeof(float));
00065     memcpy(&pointcloud_.data[2 * pointcloud_.point_step + pointcloud_.fields[1].offset], &N_INF_Y, sizeof(float));
00066   }
00067 
00068   pointcloud_.header.stamp = msg->header.stamp;
00069   pointcloud_pub_.publish(pointcloud_);
00070 }
00071 
00072 void Bumper2PcNodelet::onInit()
00073 {
00074   ros::NodeHandle nh = this->getPrivateNodeHandle();
00075 
00076   // Bumper/cliff pointcloud distance to base frame; should be something like the robot radius plus
00077   // costmap resolution plus an extra to cope with robot inertia. This is a bit tricky parameter: if
00078   // it's too low, costmap will ignore this pointcloud (the robot footprint runs over the hit obstacle),
00079   // but if it's too big, hit obstacles will be mapped too far from the robot and the navigation around
00080   // them will probably fail.
00081   double r, h;
00082   nh.param("pointcloud_radius", r, 0.25); pc_radius_ = r;
00083   nh.param("pointcloud_height", h, 0.04); pc_height_ = h;
00084 
00085   // Lateral points x/y coordinates; we need to store float values to memcopy later
00086   p_side_x_ = + pc_radius_*sin(0.34906585); // 20 degrees from vertical
00087   p_side_y_ = + pc_radius_*cos(0.34906585); // 20 degrees from vertical
00088   n_side_y_ = - pc_radius_*cos(0.34906585); // 20 degrees from vertical
00089 
00090   // Prepare constant parts of the pointcloud message to be  published
00091   pointcloud_.header.frame_id = "/base_link";
00092   pointcloud_.width  = 3;
00093   pointcloud_.height = 1;
00094   pointcloud_.fields.resize(3);
00095 
00096   // Set x/y/z as the only fields
00097   pointcloud_.fields[0].name = "x";
00098   pointcloud_.fields[1].name = "y";
00099   pointcloud_.fields[2].name = "z";
00100 
00101   int offset = 0;
00102   // All offsets are *4, as all field data types are float32
00103   for (size_t d = 0; d < pointcloud_.fields.size(); ++d, offset += 4)
00104   {
00105     pointcloud_.fields[d].count    = 1;
00106     pointcloud_.fields[d].offset   = offset;
00107     pointcloud_.fields[d].datatype = sensor_msgs::PointField::FLOAT32;
00108   }
00109 
00110   pointcloud_.point_step = offset;
00111   pointcloud_.row_step   = pointcloud_.point_step * pointcloud_.width;
00112 
00113   pointcloud_.data.resize(3 * pointcloud_.point_step);
00114   pointcloud_.is_bigendian = false;
00115   pointcloud_.is_dense     = true;
00116 
00117   // Bumper/cliff "points" fix coordinates (the others depend on sensor activation/deactivation)
00118 
00119   // y: always 0 for central bumper
00120   memcpy(&pointcloud_.data[1 * pointcloud_.point_step + pointcloud_.fields[1].offset], &ZERO, sizeof(float));
00121 
00122   // z: constant elevation from base frame
00123   memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[2].offset], &pc_height_, sizeof(float));
00124   memcpy(&pointcloud_.data[1 * pointcloud_.point_step + pointcloud_.fields[2].offset], &pc_height_, sizeof(float));
00125   memcpy(&pointcloud_.data[2 * pointcloud_.point_step + pointcloud_.fields[2].offset], &pc_height_, sizeof(float));
00126 
00127   pointcloud_pub_  = nh.advertise <sensor_msgs::PointCloud2> ("pointcloud", 10);
00128   core_sensor_sub_ = nh.subscribe("core_sensors", 10, &Bumper2PcNodelet::coreSensorCB, this);
00129 
00130   ROS_INFO("Bumper/cliff pointcloud configured at distance %f and height %f from base frame", pc_radius_, pc_height_);
00131 }
00132 
00133 } // namespace kobuki_bumper2pc
00134 
00135 
00136 PLUGINLIB_EXPORT_CLASS(kobuki_bumper2pc::Bumper2PcNodelet, nodelet::Nodelet);


kobuki_bumper2pc
Author(s): Jorge Santos Simon
autogenerated on Wed Sep 16 2015 04:35:16