33 #include "visualization_msgs/MarkerArray.h" 35 #include "nav_msgs/MapMetaData.h" 36 #include "sensor_msgs/LaserScan.h" 37 #include "nav_msgs/GetMap.h" 43 #include <boost/thread.hpp> 50 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) 58 void laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan);
60 nav_msgs::GetMap::Response &res);
66 const sensor_msgs::LaserScan::ConstPtr& scan,
85 nav_msgs::GetMap::Response
map_;
101 std::map<std::string, karto::LaserRangeFinder*>
lasers_;
131 if(!private_nh_.
getParam(
"map_update_interval", tmp))
141 double transform_publish_period;
142 private_nh_.
param(
"transform_publish_period", transform_publish_period, 0.05);
152 marker_publisher_ = node_.advertise<visualization_msgs::MarkerArray>(
"visualization_marker_array",1);
164 bool use_scan_matching;
165 if(private_nh_.
getParam(
"use_scan_matching", use_scan_matching))
168 bool use_scan_barycenter;
169 if(private_nh_.
getParam(
"use_scan_barycenter", use_scan_barycenter))
172 double minimum_travel_distance;
173 if(private_nh_.
getParam(
"minimum_travel_distance", minimum_travel_distance))
176 double minimum_travel_heading;
177 if(private_nh_.
getParam(
"minimum_travel_heading", minimum_travel_heading))
180 int scan_buffer_size;
181 if(private_nh_.
getParam(
"scan_buffer_size", scan_buffer_size))
184 double scan_buffer_maximum_scan_distance;
185 if(private_nh_.
getParam(
"scan_buffer_maximum_scan_distance", scan_buffer_maximum_scan_distance))
188 double link_match_minimum_response_fine;
189 if(private_nh_.
getParam(
"link_match_minimum_response_fine", link_match_minimum_response_fine))
192 double link_scan_maximum_distance;
193 if(private_nh_.
getParam(
"link_scan_maximum_distance", link_scan_maximum_distance))
196 double loop_search_maximum_distance;
197 if(private_nh_.
getParam(
"loop_search_maximum_distance", loop_search_maximum_distance))
200 bool do_loop_closing;
201 if(private_nh_.
getParam(
"do_loop_closing", do_loop_closing))
204 int loop_match_minimum_chain_size;
205 if(private_nh_.
getParam(
"loop_match_minimum_chain_size", loop_match_minimum_chain_size))
208 double loop_match_maximum_variance_coarse;
209 if(private_nh_.
getParam(
"loop_match_maximum_variance_coarse", loop_match_maximum_variance_coarse))
212 double loop_match_minimum_response_coarse;
213 if(private_nh_.
getParam(
"loop_match_minimum_response_coarse", loop_match_minimum_response_coarse))
216 double loop_match_minimum_response_fine;
217 if(private_nh_.
getParam(
"loop_match_minimum_response_fine", loop_match_minimum_response_fine))
222 double correlation_search_space_dimension;
223 if(private_nh_.
getParam(
"correlation_search_space_dimension", correlation_search_space_dimension))
226 double correlation_search_space_resolution;
227 if(private_nh_.
getParam(
"correlation_search_space_resolution", correlation_search_space_resolution))
230 double correlation_search_space_smear_deviation;
231 if(private_nh_.
getParam(
"correlation_search_space_smear_deviation", correlation_search_space_smear_deviation))
236 double loop_search_space_dimension;
237 if(private_nh_.
getParam(
"loop_search_space_dimension", loop_search_space_dimension))
240 double loop_search_space_resolution;
241 if(private_nh_.
getParam(
"loop_search_space_resolution", loop_search_space_resolution))
244 double loop_search_space_smear_deviation;
245 if(private_nh_.
getParam(
"loop_search_space_smear_deviation", loop_search_space_smear_deviation))
250 double distance_variance_penalty;
251 if(private_nh_.
getParam(
"distance_variance_penalty", distance_variance_penalty))
254 double angle_variance_penalty;
255 if(private_nh_.
getParam(
"angle_variance_penalty", angle_variance_penalty))
258 double fine_search_angle_offset;
259 if(private_nh_.
getParam(
"fine_search_angle_offset", fine_search_angle_offset))
262 double coarse_search_angle_offset;
263 if(private_nh_.
getParam(
"coarse_search_angle_offset", coarse_search_angle_offset))
266 double coarse_angle_resolution;
267 if(private_nh_.
getParam(
"coarse_angle_resolution", coarse_angle_resolution))
270 double minimum_angle_penalty;
271 if(private_nh_.
getParam(
"minimum_angle_penalty", minimum_angle_penalty))
274 double minimum_distance_penalty;
275 if(private_nh_.
getParam(
"minimum_distance_penalty", minimum_distance_penalty))
278 bool use_response_expansion;
279 if(private_nh_.
getParam(
"use_response_expansion", use_response_expansion))
311 if(transform_publish_period == 0)
314 ros::Rate r(1.0 / transform_publish_period);
343 ident.
stamp_ = scan->header.stamp;
350 ROS_WARN(
"Failed to compute laser pose, aborting initialization (%s)",
355 double yaw =
tf::getYaw(laser_pose.getRotation());
357 ROS_INFO(
"laser %s's pose wrt base: %.3f %.3f %.3f",
358 scan->header.frame_id.c_str(),
359 laser_pose.getOrigin().x(),
360 laser_pose.getOrigin().y(),
367 v.
setValue(0, 0, 1 + laser_pose.getOrigin().z());
373 ROS_DEBUG(
"Z-Axis in sensor frame: %.3f", up.z());
377 ROS_WARN(
"Unable to determine orientation of laser: %s", e.what());
383 ROS_INFO(
"laser is mounted upside-down");
388 std::string name = scan->header.frame_id;
392 laser_pose.getOrigin().y(),
403 lasers_[scan->header.frame_id] = laser;
409 return lasers_[scan->header.frame_id];
425 ROS_WARN(
"Failed to compute odom pose, skipping scan (%s)", e.what());
428 double yaw =
tf::getYaw(odom_pose.getRotation());
432 odom_pose.getOrigin().y(),
440 std::vector<float> graph;
443 visualization_msgs::MarkerArray marray;
445 visualization_msgs::Marker m;
446 m.header.frame_id =
"map";
450 m.type = visualization_msgs::Marker::SPHERE;
451 m.pose.position.x = 0.0;
452 m.pose.position.y = 0.0;
453 m.pose.position.z = 0.0;
463 visualization_msgs::Marker edge;
464 edge.header.frame_id =
"map";
466 edge.action = visualization_msgs::Marker::ADD;
469 edge.type = visualization_msgs::Marker::LINE_STRIP;
478 m.action = visualization_msgs::Marker::ADD;
480 for (uint i=0; i<graph.size()/2; i++)
483 m.pose.position.x = graph[2*i];
484 m.pose.position.y = graph[2*i+1];
485 marray.markers.push_back(visualization_msgs::Marker(m));
492 geometry_msgs::Point p;
493 p.x = graph[2*(i-1)];
494 p.y = graph[2*(i-1)+1];
495 edge.points.push_back(p);
498 edge.points.push_back(p);
501 marray.markers.push_back(visualization_msgs::Marker(edge));
506 m.action = visualization_msgs::Marker::DELETE;
510 marray.markers.push_back(visualization_msgs::Marker(m));
513 marker_count_ = marray.markers.size();
532 ROS_WARN(
"Failed to create laser device for %s; discarding scan",
533 scan->header.frame_id.c_str());
538 if(
addScan(laser, scan, odom_pose))
540 ROS_DEBUG(
"added scan at pose: %.3f %.3f %.3f",
552 last_map_update = scan->header.stamp;
573 map_.map.info.origin.position.x = 0.0;
574 map_.map.info.origin.position.y = 0.0;
575 map_.map.info.origin.position.z = 0.0;
576 map_.map.info.origin.orientation.x = 0.0;
577 map_.map.info.origin.orientation.y = 0.0;
578 map_.map.info.origin.orientation.z = 0.0;
579 map_.map.info.origin.orientation.w = 1.0;
587 if(
map_.map.info.width != (
unsigned int) width ||
588 map_.map.info.height != (
unsigned int) height ||
589 map_.map.info.origin.position.x != offset.
GetX() ||
590 map_.map.info.origin.position.y != offset.
GetY())
592 map_.map.info.origin.position.x = offset.
GetX();
593 map_.map.info.origin.position.y = offset.
GetY();
594 map_.map.info.width = width;
595 map_.map.info.height = height;
596 map_.map.data.resize(
map_.map.info.width *
map_.map.info.height);
618 ROS_WARN(
"Encountered unknown cell value at %d, %d",
x,
y);
638 const sensor_msgs::LaserScan::ConstPtr& scan,
645 std::vector<kt_double> readings;
648 for(std::vector<float>::const_reverse_iterator it = scan->ranges.rbegin();
649 it != scan->ranges.rend();
652 readings.push_back(*it);
655 for(std::vector<float>::const_iterator it = scan->ranges.begin();
656 it != scan->ranges.end();
659 readings.push_back(*it);
687 ROS_ERROR(
"Transform from base_link to odom failed\n");
688 odom_to_map.setIdentity();
708 nav_msgs::GetMap::Response &res)
kt_int32s GetHeight() const
virtual kt_bool Process(LocalizedRangeScan *pScan)
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
void setParamCorrelationSearchSpaceResolution(double d)
void setParamLoopMatchMinimumChainSize(int i)
kt_double GetHeading() const
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
void setParamUseScanMatching(bool b)
static double getYaw(const Quaternion &bt_q)
ros::Publisher marker_publisher_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setParamDoLoopClosing(bool b)
Pose2(const Pose3 &rPose)
void setParamCorrelationSearchSpaceSmearDeviation(double d)
kt_int32s GetWidth() const
void setParamDistanceVariancePenalty(double d)
std::map< std::string, bool > lasers_inverted_
const Name & GetName() const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
void setParamScanBufferSize(int i)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void setParamCorrelationSearchSpaceDimension(double d)
void SetMinimumAngle(kt_double minimumAngle)
TFSIMD_FORCE_INLINE void setValue(const tfScalar &x, const tfScalar &y, const tfScalar &z)
void SetMaximumRange(kt_double maximumRange)
void SetOffsetPose(const Pose2 &rPose)
ROSCPP_DECL void spin(Spinner &spinner)
void setParamAngleVariancePenalty(double d)
void publishGraphVisualization()
void setParamLoopMatchMaximumVarianceCoarse(double d)
void SetAngularResolution(kt_double angularResolution)
void Add(Object *pObject)
void setParamLinkScanMaximumDistance(double d)
void setParamMinimumAnglePenalty(double d)
tf::Transform map_to_odom_
void SetMaximumAngle(kt_double maximumAngle)
Duration & fromSec(double t)
bool getOdomPose(karto::Pose2 &karto_pose, const ros::Time &t)
void setParamLoopSearchSpaceDimension(double d)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void setParamLoopSearchSpaceResolution(double d)
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
std::map< std::string, karto::LaserRangeFinder * > lasers_
void setParamScanBufferMaximumScanDistance(double d)
void setParamMinimumDistancePenalty(double d)
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
ros::Duration map_update_interval_
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
void setParamLoopSearchMaximumDistance(double d)
TFSIMD_FORCE_INLINE const tfScalar & x() const
karto::Dataset * dataset_
void setParamLoopMatchMinimumResponseCoarse(double d)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setParamMinimumTravelDistance(double d)
tf::TransformBroadcaster * tfB_
static OccupancyGrid * CreateFromScans(const LocalizedRangeScanVector &rScans, kt_double resolution)
void SetScanSolver(ScanSolver *pSolver)
virtual const LocalizedRangeScanVector GetAllProcessedScans() const
void SetOdometricPose(const Pose2 &rPose)
static LaserRangeFinder * CreateLaserRangeFinder(LaserRangeFinderType type, const Name &rName)
void setParamLinkMatchMinimumResponseFine(double d)
bool addScan(karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
CoordinateConverter * GetCoordinateConverter() const
void setParamCoarseSearchAngleOffset(double d)
void SetMinimumRange(kt_double minimumRange)
boost::mutex map_to_odom_mutex_
karto::LaserRangeFinder * getLaser(const sensor_msgs::LaserScan::ConstPtr &scan)
void SetCorrectedPose(const Pose2 &rPose)
void setParamFineSearchAngleOffset(double d)
bool getParam(const std::string &key, std::string &s) const
#define MAP_IDX(sx, i, j)
void publishLoop(double transform_publish_period)
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
tf::TransformListener tf_
kt_int8u GetValue(const Vector2< kt_int32s > &rGrid) const
nav_msgs::GetMap::Response map_
void setParamMinimumTravelHeading(double d)
void setParamUseResponseExpansion(bool b)
void setParamLoopMatchMinimumResponseFine(double d)
void setParamUseScanBarycenter(bool b)
const Pose2 & GetCorrectedPose() const
boost::thread * transform_thread_
void setParamLoopSearchSpaceSmearDeviation(double d)
Connection registerCallback(const C &callback)
void setParamCoarseAngleResolution(double d)