36 #include <mrpt/obs/CObservation2DRangeScan.h>
37 #include <mrpt/obs/CObservationBeaconRanges.h>
38 #include <mrpt/obs/CObservationBearingRange.h>
39 #include <mrpt/obs/CRawlog.h>
40 #include <mrpt/obs/CSensoryFrame.h>
41 #include <mrpt/ros1bridge/laser_scan.h>
42 #include <mrpt/ros1bridge/pose.h>
43 #include <mrpt/ros1bridge/time.h>
44 #include <mrpt/system/filesystem.h>
48 #include <boost/interprocess/sync/scoped_lock.hpp>
49 using namespace mrpt::obs;
51 #include <mrpt/serialization/CArchive.h>
53 int main(
int argc,
char** argv)
86 n_.
advertise<mrpt_msgs::ObservationRangeBearing>(
"landmark", 10);
89 robotPose = mrpt::poses::CPose3DPDFGaussian();
93 const mrpt::obs::CObservation::Ptr& o)
95 mrpt::poses::CPose3D pose_sensor;
96 o->getSensorPose(pose_sensor);
98 geometry_msgs::Pose msgSensorPose;
102 auto lambdaSendTfSensorPose = [&](
const std_msgs::Header&
header) {
104 mrpt::ros1bridge::toROS_tfTransform(pose_sensor);
106 geometry_msgs::TransformStamped tfGeom =
109 tfGeom.child_frame_id =
header.frame_id;
115 if (
auto laser = std::dynamic_pointer_cast<CObservation2DRangeScan>(o);
118 mrpt::ros1bridge::toROS(*laser,
msg_laser_, msgSensorPose);
128 else if (
auto beacon =
129 std::dynamic_pointer_cast<CObservationBeaconRanges>(o);
141 else if (
auto landmark =
142 std::dynamic_pointer_cast<CObservationBearingRange>(o);
156 "Observation mapping to ROS not implemented: %s",
157 o->GetRuntimeClass()->className);
163 CActionCollection::Ptr action;
164 CSensoryFrame::Ptr observations;
165 CObservation::Ptr obs;
169 if (!CRawlog::getActionObservationPairOrObservation(
170 rs, action, observations, obs,
entry_))
182 mrpt::poses::CPose3DPDFGaussian out_pose_increment;
183 action->getFirstMovementEstimation(out_pose_increment);
205 transform = mrpt::ros1bridge::toROS_tfTransform(
robotPose.mean);
209 MRPT_TODO(
"Publish /odom topic too?");
212 geometry_msgs::TransformStamped tfGeom =
216 tfGeom.child_frame_id =
msg_odom_.header.frame_id;