2 #include <mrpt/maps/CBeaconMap.h> 3 #include <mrpt/maps/COccupancyGridMap2D.h> 5 using mrpt::maps::CBeaconMap;
6 using mrpt::maps::COccupancyGridMap2D;
9 bool isFileExists(
const std::string &name) {
10 std::ifstream
f(name.c_str());
21 ROS_INFO(
"READ PARAM FROM LAUNCH FILE");
23 ROS_INFO(
"rawlog_play_delay: %f", rawlog_play_delay_);
32 ROS_INFO(
"global_frame_id: %s", global_frame_id_.c_str());
35 ROS_INFO(
"odom_frame_id: %s", odom_frame_id_.c_str());
38 ROS_INFO(
"base_frame_id: %s", base_frame_id_.c_str());
41 ROS_INFO(
"sensor_source: %s", sensor_source_.c_str());
45 ROS_ERROR(
"Not able to read all parameters!");
74 nh.
advertise<geometry_msgs::PoseArray>(
"particlecloud", 1,
true);
77 nh.
advertise<geometry_msgs::PoseArray>(
"particlecloud_beacons", 1,
true);
79 nh.
advertise<visualization_msgs::MarkerArray>(
"/beacons_viz", 1);
82 std::vector<std::string> lstSources;
85 "*Fatal*: At least one sensor source must be provided in " 86 "~sensor_sources (e.g. " 87 "\"scan\" or \"beacon\")");
91 for (
size_t i = 0; i < lstSources.size(); i++) {
92 if (lstSources[i].find(
"scan") != std::string::npos) {
107 mrpt::obs::CObservationOdometry::Ptr &odometry,
108 const std_msgs::Header &_msg_header) {
109 mrpt::poses::CPose3D poseOdom;
112 odometry = mrpt::obs::CObservationOdometry::Create();
114 odometry->hasEncodersInfo =
false;
115 odometry->hasVelocities =
false;
116 odometry->odometry.x() = poseOdom.x();
117 odometry->odometry.y() = poseOdom.y();
118 odometry->odometry.phi() = poseOdom.yaw();
123 mrpt::poses::CPose3D &des,
const std::string &target_frame,
124 const std::string &source_frame,
const ros::Time &time,
129 polling_sleep_duration);
132 ROS_ERROR(
"Failed to get transform target_frame (%s) to source_frame (%s). " 133 "TransformException: %s",
134 target_frame.c_str(), source_frame.c_str(), ex.what());
137 mrpt_bridge::convert(transform, des);
142 using namespace mrpt::maps;
144 CObservation2DRangeScan::Ptr laser = CObservation2DRangeScan::Create();
149 mrpt::poses::CPose3D pose =
laser_poses_[msg.header.frame_id];
150 mrpt_bridge::convert(msg,
laser_poses_[msg.header.frame_id], *laser);
153 CObservationOdometry::Ptr odometry;
156 CObservation::Ptr obs = CObservation::Ptr(laser);
172 const mrpt_msgs::ObservationRangeBeacon &msg) {
173 using namespace mrpt::maps;
176 CObservationBeaconRanges::Ptr beacon = CObservationBeaconRanges::Create();
180 mrpt_bridge::convert(msg,
beacon_poses_[msg.header.frame_id], *beacon);
183 CObservationOdometry::Ptr odometry;
186 CObservation::Ptr obs = CObservation::Ptr(beacon);
207 COccupancyGridMap2D *grid =
nullptr;
208 CBeaconMap *bm =
nullptr;
209 #if MRPT_VERSION >= 0x199 210 if (
metric_map_->countMapsByClass<COccupancyGridMap2D>())
211 grid =
metric_map_->mapByClass<COccupancyGridMap2D>().
get();
216 bm =
metric_map_->getMapByClass<CBeaconMap>().
get();
221 nav_msgs::OccupancyGrid msg;
222 mrpt_bridge::convert(*grid, msg);
229 mrpt::opengl::CSetOfObjects::Ptr objs;
231 objs = mrpt::opengl::CSetOfObjects::Create();
233 bm->getAs3DObject(objs);
235 geometry_msgs::PoseArray poseArrayBeacons;
240 unsigned int objs_counter = 0;
241 while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter)) {
244 poseArrayBeacons.poses.resize(objs_counter);
245 mrpt::opengl::CEllipsoid::Ptr beacon_particle;
247 for (
size_t i = 0; i < objs_counter; i++) {
248 beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
249 mrpt_bridge::convert(mrpt::poses::CPose3D(beacon_particle->getPose()),
250 poseArrayBeacons.poses[i]);
259 geometry_msgs::PoseArray poseArray;
262 poseArray.poses.resize(
curPDF.particlesCount());
263 for (
size_t i = 0; i <
curPDF.particlesCount(); i++) {
264 const auto p = mrpt::poses::CPose3D(
curPDF.getParticlePose(i));
265 mrpt_bridge::convert(p, poseArray.poses[i]);
275 visualization_msgs::MarkerArray ma;
276 visualization_msgs::Marker marker;
278 marker.header.frame_id =
"/map";
281 marker.type = visualization_msgs::Marker::SPHERE;
282 marker.action = visualization_msgs::Marker::ADD;
284 marker.pose.position.x = 0;
285 marker.pose.position.y = 0;
286 marker.pose.position.z = 0;
287 marker.pose.orientation.x = 0.0;
288 marker.pose.orientation.y = 0.0;
289 marker.pose.orientation.z = 0.0;
290 marker.pose.orientation.w = 1.0;
291 marker.scale.x = 0.12;
292 marker.scale.y = 0.12;
293 marker.scale.z = 0.12;
294 marker.color.a = 1.0;
295 marker.color.r = 1.0;
296 marker.color.g = 0.0;
298 for (
unsigned int i = 0; i <
viz_beacons_.size(); i++) {
299 mrpt::poses::CPose3D meanPose(
viz_beacons_[i]->getPose());
300 marker.type = visualization_msgs::Marker::SPHERE;
302 marker.pose.position.x = meanPose.x();
303 marker.pose.position.y = meanPose.y();
304 marker.pose.position.z = meanPose.z();
305 marker.color.r = 1.0;
306 marker.color.g = 0.0;
307 marker.color.b = 0.0;
309 ma.markers.push_back(marker);
312 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
313 marker.text = std::to_string(i);
315 marker.pose.position.x = meanPose.x();
316 marker.pose.position.y = meanPose.y();
317 marker.pose.position.z = meanPose.z() + 0.12;
318 marker.color.r = 1.0;
319 marker.color.g = 1.0;
320 marker.color.b = 1.0;
322 ma.markers.push_back(marker);
330 mrpt::poses::CPose3D pose;
338 pose.x() = translation.
x();
339 pose.y() = translation.
y();
340 pose.z() = translation.
z();
342 mrpt::math::CMatrixDouble33 Rdes;
343 for (
int c = 0; c < 3; c++)
344 for (
int r = 0;
r < 3;
r++)
346 pose.setRotationMatrix(Rdes);
359 for (
unsigned int i = 0; i <
data_.size(); i++) {
371 COccupancyGridMap2D *grid =
nullptr;
372 CBeaconMap *bm =
nullptr;
373 #if MRPT_VERSION >= 0x199 374 if (
metric_map_->countMapsByClass<COccupancyGridMap2D>())
375 grid =
metric_map_->mapByClass<COccupancyGridMap2D>().
get();
380 bm =
metric_map_->getMapByClass<CBeaconMap>().
get();
385 nav_msgs::OccupancyGrid msg;
387 mrpt_bridge::convert(*grid, msg);
394 mrpt::opengl::CSetOfObjects::Ptr objs;
395 objs = mrpt::opengl::CSetOfObjects::Create();
396 bm->getAs3DObject(objs);
398 geometry_msgs::PoseArray poseArrayBeacons;
402 unsigned int objs_counter = 0;
403 while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter)) {
406 poseArrayBeacons.poses.resize(objs_counter);
407 mrpt::opengl::CEllipsoid::Ptr beacon_particle;
409 for (
size_t i = 0; i < objs_counter; i++) {
410 beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
411 mrpt_bridge::convert(
412 mrpt::poses::CPose3D(beacon_particle->getPose()),
413 poseArrayBeacons.poses[i]);
422 geometry_msgs::PoseArray poseArray;
425 poseArray.poses.resize(
curPDF.particlesCount());
426 for (
size_t i = 0; i <
curPDF.particlesCount(); i++) {
427 const auto p = mrpt::poses::CPose3D(
curPDF.getParticlePose(i));
428 mrpt_bridge::convert(p, poseArray.poses[i]);
446 mrpt::poses::CPose3D robotPose;
449 curPDF.getMean(robotPose);
455 mrpt_bridge::convert(robotPose, tmp_tf);
462 ROS_ERROR(
"Failed to subtract global_frame (%s) from odom_frame (%s). " 463 "TransformException: %s",
476 ros::Time transform_expiration = (stamp + transform_tolerance_);
std::string global_frame_id_
/map frame
tf::TransformListener listenerTF_
transform listener
void odometryForCallback(mrpt::obs::CObservationOdometry::Ptr &odometry, const std_msgs::Header &msg_header)
Get the odometry for received observation.
std::vector< ros::Subscriber > sensorSub_
list of sensors topics
mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions rbpfMappingOptions_
options for SLAM from ini file
mrpt::utils::CTicTac tictac_
void observation(const mrpt::obs::CSensoryFrame::ConstPtr sensory_frame, const mrpt::obs::CObservationOdometry::ConstPtr odometry)
Calculate the actions from odometry model for current observation.
void publish(const boost::shared_ptr< M > &message) const
bool rawlogPlay()
Play rawlog file.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string rawlog_filename_
name of rawlog file
std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame > > data_
void laserCallback(const sensor_msgs::LaserScan &msg)
Callback function for the laser scans.
ros::Publisher beacon_viz_pub_
publishers for map and pose particles
mrpt::poses::CPose3DPDFParticles curPDF
current robot pose
std::string odom_frame_id_
/odom frame
void vizBeacons()
Correct visualization for ro slam.
bool getParams(const ros::NodeHandle &nh_p)
Read the parameters from launch file.
ros::Publisher pub_metadata_
float t_exec_
the time which take one SLAM update execution
void publishTF()
Publish tf tree.
void publishMapPose()
Publish beacon or grid map and robot pose.
std::map< std::string, mrpt::poses::CPose3D > beacon_poses_
beacon poses with respect to the map
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))
Wait for transform between odometry frame and the robot frame.
bool init(ros::NodeHandle &nh)
Initialize publishers subscribers and RBPF slam.
mrpt::gui::CDisplayWindow3D::Ptr win3D_
MRPT window.
ros::Publisher pub_particles_
TFSIMD_FORCE_INLINE const Vector3 & getRow(int i) const
struct mrpt_rbpf_slam::PFslam::Options options_
mrpt::obs::CSensoryFrame::Ptr sensory_frame_
observations
void readIniFile(const std::string &ini_filename)
Read ini file.
mrpt::slam::CMetricMapBuilderRBPF mapBuilder_
map builder
void updateSensorPose(const std::string &frame_id)
Update the pose of the sensor with respect to the robot.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void initSlam(Options options)
initialize the SLAM
TFSIMD_FORCE_INLINE const tfScalar & z() const
void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon &msg)
Callback function for the beacons.
mrpt::obs::CActionCollection::Ptr action_
actions
std::string sensor_source_
2D laser scans
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define ROS_ASSERT_MSG(cond,...)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void readRawlog(const std::string &rawlog_filename, std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame >> &data)
Read pairs of actions and observations from rawlog file.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double rawlog_play_delay_
delay of replay from rawlog file
#define ROS_WARN_STREAM(args)
bool loadOptions(const ros::NodeHandle &nh, PFslam::Options &options)
mrpt::system::TTimeStamp timeLastUpdate_
last update of the pose and map
const mrpt::maps::CMultiMetricMap * metric_map_
receive map after iteration of SLAM to metric map
bool rawlog_play_
true if rawlog file exists
std::map< std::string, mrpt::poses::CPose3D > laser_poses_
laser scan poses with respect to the map
std::string ini_filename_
name of ini file
bool getParam(const std::string &key, std::string &s) const
ros::Publisher pub_particles_beacons_
tf::TransformBroadcaster tf_broadcaster_
transform broadcaster
std::vector< mrpt::opengl::CEllipsoid::Ptr > viz_beacons_
std::string base_frame_id_
robot frame
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()