34 #include <boost/interprocess/sync/scoped_lock.hpp> 35 #include <geometry_msgs/PoseArray.h> 36 #include <pose_cov_ops/pose_cov_ops.h> 38 #include <mrpt_bridge/pose.h> 39 #include <mrpt_bridge/laser_scan.h> 40 #include <mrpt_bridge/time.h> 41 #include <mrpt_bridge/map.h> 42 #include <mrpt_bridge/beacon.h> 44 #include <mrpt/version.h> 45 #include <mrpt/obs/CObservationBeaconRanges.h> 48 #include <mrpt/version.h> 50 #if MRPT_VERSION >= 0x199 51 #include <mrpt/system/COutputLogger.h> 54 #include <mrpt/utils/COutputLogger.h> 58 #include <mrpt/obs/CObservationRobotPose.h> 62 #include <mrpt/maps/COccupancyGridMap2D.h> 63 using mrpt::maps::COccupancyGridMap2D;
65 int main(
int argc,
char** argv)
79 first_map_received_(false),
103 std::vector<std::string> sources;
104 mrpt::system::tokenize(
param()->sensor_sources,
" ,\t\n", sources);
107 "*Fatal*: At least one sensor source must be provided in " 108 "~sensor_sources (e.g. \"scan\" or \"beacon\")");
110 for (
size_t i = 0; i < sources.size(); i++)
112 if (sources[i].find(
"scan") != std::string::npos)
117 else if (sources[i].find(
"beacon") != std::string::npos)
129 if (!
param()->map_file.empty())
131 #if MRPT_VERSION >= 0x199 132 if (
metric_map_.countMapsByClass<COccupancyGridMap2D>())
134 mrpt_bridge::convert(
145 nh_.
advertise<nav_msgs::MapMetaData>(
"map_metadata", 1,
true);
150 nh_.
advertise<geometry_msgs::PoseArray>(
"particlecloud", 1,
true);
153 "mrpt_pose", 2,
true);
164 #
if MRPT_VERSION >= 0x199
165 (
metric_map_.countMapsByClass<COccupancyGridMap2D>()))
181 mrpt::poses::CPose3D& des,
const std::string& target_frame,
182 const std::string& source_frame,
const ros::Time& time,
189 target_frame, source_frame, time, timeout, polling_sleep_duration);
191 target_frame, source_frame, time, transform);
196 "Failed to get transform target_frame (%s) to source_frame (%s): " 198 target_frame.c_str(), source_frame.c_str(), e.what());
201 mrpt_bridge::convert(transform, des);
213 auto laser = CObservation2DRangeScan::Create();
226 mrpt_bridge::convert(_msg,
laser_poses_[_msg.header.frame_id], *laser);
228 auto sf = CSensoryFrame::Create();
229 CObservationOdometry::Ptr odometry;
232 CObservation::Ptr obs = CObservation::Ptr(laser);
240 const mrpt_msgs::ObservationRangeBeacon& _msg)
248 auto beacon = CObservationBeaconRanges::Create();
260 mrpt_bridge::convert(
263 auto sf = CSensoryFrame::Create();
264 CObservationOdometry::Ptr odometry;
267 CObservation::Ptr obs = CObservation::Ptr(beacon);
275 const geometry_msgs::PoseWithCovarianceStamped& _msg)
289 static std::string base_frame_id =
291 static std::string global_frame_id =
298 global_frame_id, _msg.header.frame_id,
ros::Time(0.0),
301 global_frame_id, _msg.header.frame_id,
ros::Time(0.0),
314 geometry_msgs::Pose map_to_obs_pose;
317 map_to_obs_tf.
getRotation(), map_to_obs_pose.orientation);
318 geometry_msgs::PoseWithCovarianceStamped obs_pose_world;
319 obs_pose_world.header.stamp = _msg.header.stamp;
320 obs_pose_world.header.frame_id = global_frame_id;
321 pose_cov_ops::compose(map_to_obs_pose, _msg.pose, obs_pose_world.pose);
324 for (
unsigned int i = 0; i < obs_pose_world.pose.covariance.size(); ++i)
326 if (i / 6 == i % 6 && obs_pose_world.pose.covariance[i] <= 0.0)
327 obs_pose_world.pose.covariance[i] =
328 std::numeric_limits<double>().infinity();
332 auto feature = CObservationRobotPose::Create();
334 feature->sensorLabel = _msg.header.frame_id;
335 mrpt_bridge::convert(_msg.header.stamp, feature->timestamp);
336 mrpt_bridge::convert(obs_pose_world.pose, feature->pose);
338 auto sf = CSensoryFrame::Create();
339 CObservationOdometry::Ptr odometry;
342 CObservation::Ptr obs = CObservation::Ptr(feature);
349 CObservationOdometry::Ptr& _odometry,
const std_msgs::Header& _msg_header)
351 std::string base_frame_id =
353 std::string odom_frame_id =
355 mrpt::poses::CPose3D poseOdom;
357 poseOdom, odom_frame_id, base_frame_id, _msg_header.stamp,
360 _odometry = CObservationOdometry::Create();
361 _odometry->sensorLabel = odom_frame_id;
362 _odometry->hasEncodersInfo =
false;
363 _odometry->hasVelocities =
false;
364 _odometry->odometry.x() = poseOdom.x();
365 _odometry->odometry.y() = poseOdom.y();
366 _odometry->odometry.phi() = poseOdom.yaw();
372 int wait_counter = 0;
375 if (
param()->use_map_topic)
379 ROS_INFO(
"Subscribed to map topic.");
383 ROS_INFO(
"waiting for map callback..");
388 if (wait_counter != wait_limit)
396 nav_msgs::GetMap srv;
399 ROS_INFO(
"waiting for map service!");
404 if (wait_counter != wait_limit)
431 mrpt::poses::CPose3D pose;
435 std::string base_frame_id =
438 base_frame_id, _frame_id,
ros::Time(0), transform);
441 pose.x() = translation.
x();
442 pose.y() = translation.
y();
443 pose.z() = translation.
z();
445 mrpt::math::CMatrixDouble33 Rdes;
446 for (
int c = 0; c < 3; c++)
447 for (
int r = 0; r < 3; r++) Rdes(r, c) = Rsrc.
getRow(r)[c];
448 pose.setRotationMatrix(Rdes);
460 const geometry_msgs::PoseWithCovarianceStamped& _msg)
462 const geometry_msgs::PoseWithCovariance& pose = _msg.pose;
474 bool moving = std::abs(_msg.twist.twist.linear.x) > 1e-3 ||
475 std::abs(_msg.twist.twist.linear.y) > 1e-3 ||
476 std::abs(_msg.twist.twist.linear.z) > 1e-3 ||
477 std::abs(_msg.twist.twist.angular.x) > 1e-3 ||
478 std::abs(_msg.twist.twist.angular.y) > 1e-3 ||
479 std::abs(_msg.twist.twist.angular.z) > 1e-3;
480 if (
param()->update_while_stopped || moving)
495 #if MRPT_VERSION >= 0x199 496 ASSERT_(
metric_map_.countMapsByClass<COccupancyGridMap2D>());
497 mrpt_bridge::convert(_msg, *
metric_map_.mapByClass<COccupancyGridMap2D>());
500 mrpt_bridge::convert(_msg, *
metric_map_.m_gridMaps[0]);
505 nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res)
507 ROS_INFO(
"mapCallback: service requested!\n");
515 resp_.map.header.frame_id =
532 geometry_msgs::PoseArray poseArray;
533 poseArray.header.frame_id =
537 poseArray.poses.resize(
pdf_.particlesCount());
538 for (
size_t i = 0; i <
pdf_.particlesCount(); i++)
540 mrpt::math::TPose2D p =
pdf_.getParticlePose(i);
541 mrpt_bridge::convert(p, poseArray.poses[i]);
543 mrpt::poses::CPose2D p;
554 static std::string base_frame_id =
556 static std::string odom_frame_id =
558 static std::string global_frame_id =
561 mrpt::poses::CPose2D robot_pose;
562 pdf_.getMean(robot_pose);
564 mrpt_bridge::convert(robot_pose, base_on_map_tf);
577 param()->no_update_tolerance)
580 param()->no_inputs_tolerance)
584 "No observations received for %.2fs (tolerance %.2fs); are " 585 "robot sensors working?",
587 param()->no_inputs_tolerance);
593 "No filter updates for %.2fs (tolerance %.2fs); probably " 594 "robot stopped for a while",
596 param()->no_update_tolerance);
607 base_frame_id, odom_frame_id, time_last_update,
ros::Duration(0.1));
609 base_frame_id, odom_frame_id, time_last_update, odom_on_base_tf);
614 2.0,
"Transform from base frame (%s) to odom frame (%s) failed: %s",
615 base_frame_id.c_str(), odom_frame_id.c_str(), e.what());
618 "Ensure that your mobile base driver is broadcasting %s -> %s tf",
619 odom_frame_id.c_str(), base_frame_id.c_str());
629 base_on_map_tf * odom_on_base_tf, transform_expiration, global_frame_id,
640 #if MRPT_VERSION >= 0x199 641 const auto [cov, mean] =
initial_pose_.getCovarianceAndMean();
643 mrpt::math::CMatrixDouble33 cov;
644 mrpt::poses::CPose2D mean;
648 geometry_msgs::PoseWithCovarianceStamped p;
660 mrpt_bridge::convert(mean, p.pose.pose);
663 for (
int i = 0; i < 3; i++)
665 for (
int j = 0; j < 3; j++)
669 if (i == 2 || j == 2)
671 ros_i = i == 2 ? 5 : i;
672 ros_j = j == 2 ? 5 : j;
674 p.pose.covariance[ros_i * 6 + ros_j] = cov(i, j);
685 std::map<std::string, ros::console::levels::Level> loggers;
687 if (loggers.find(
"ros.roscpp") != loggers.end())
688 pdf_.setVerbosityLevel(
689 static_cast<VerbosityLevel>(loggers[
"ros.roscpp"]));
690 if (loggers.find(
"ros.mrpt_localization") != loggers.end())
691 pdf_.setVerbosityLevel(
692 static_cast<VerbosityLevel>(loggers[
"ros.mrpt_localization"]));
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
CMultiMetricMap metric_map_
map
void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped &)
ros::ServiceClient client_map_
void publish(const boost::shared_ptr< M > &message) const
void publishTF()
Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_init_pose_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCONSOLE_DECL bool get_loggers(std::map< std::string, levels::Level > &loggers)
virtual bool waitForMap()
ros::Time time_last_input_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void publishPose()
Publish the current pose of the robot.
ros::Publisher pub_particles_
void observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
ros::Publisher pub_metadata_
TFSIMD_FORCE_INLINE const Vector3 & getRow(int i) const
std::string resolve(const std::string &prefix, const std::string &frame_name)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void updateSensorPose(std::string frame_id)
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_WARN_THROTTLE(period,...)
std::map< std::string, mrpt::poses::CPose3D > beacon_poses_
void odometryForCallback(CObservationOdometry::Ptr &, const std_msgs::Header &)
void callbackOdometry(const nav_msgs::Odometry &)
#define ROS_ASSERT_MSG(cond,...)
mrpt::slam::CMonteCarloLocalization2D pdf_
the filter
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
mrpt::poses::CPosePDFGaussian initial_pose_
initial posed used in initializeFilter()
TFSIMD_FORCE_INLINE const tfScalar & y() const
tf::TransformListener tf_listener_
bool waitForTransform(mrpt::poses::CPose3D &des, const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01))
std::vector< ros::Subscriber > sub_sensors_
ros::Subscriber sub_odometry_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
PFLocalizationNode(ros::NodeHandle &n)
#define ROS_WARN_STREAM(args)
void callbackLaser(const sensor_msgs::LaserScan &)
void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon &)
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
tf::TransformBroadcaster tf_broadcaster_
double transform_tolerance
unsigned long long loop_count_
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
void show3DDebug(CSensoryFrame::Ptr _observations)
nav_msgs::GetMap::Response resp_
void update(const unsigned long &loop_count)
ros::ServiceServer service_map_
virtual ~PFLocalizationNode()
std::map< std::string, mrpt::poses::CPose3D > laser_poses_
void updateMap(const nav_msgs::OccupancyGrid &)
mrpt::system::TTimeStamp time_last_update_
time of the last update
void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped &)
ROSCPP_DECL void spinOnce()
void callbackMap(const nav_msgs::OccupancyGrid &)
#define ROS_DEBUG_THROTTLE(period,...)
static void pointTFToMsg(const Point &bt_v, geometry_msgs::Point &msg_v)