35 #include <boost/interprocess/sync/scoped_lock.hpp> 36 #include <mrpt_bridge/pose.h> 37 #include <mrpt_bridge/laser_scan.h> 38 #include <mrpt_bridge/time.h> 39 #include <mrpt_bridge/beacon.h> 40 #include <mrpt_bridge/landmark.h> 41 #include <mrpt/system/filesystem.h> 43 #include <mrpt/version.h> 44 #include <mrpt/obs/CSensoryFrame.h> 45 #include <mrpt/obs/CRawlog.h> 46 #include <mrpt/obs/CObservation2DRangeScan.h> 47 #include <mrpt/obs/CObservationBeaconRanges.h> 48 #include <mrpt/obs/CObservationBearingRange.h> 51 #if MRPT_VERSION >= 0x199 52 #include <mrpt/serialization/CArchive.h> 55 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 msg_pose_sensor;
101 if (IS_CLASS(o, CObservation2DRangeScan))
103 auto laser = mrpt::ptr_cast<CObservation2DRangeScan>::from(o);
104 mrpt_bridge::convert(*laser,
msg_laser_, msg_pose_sensor);
107 std::string childframe =
110 mrpt_bridge::convert(pose_sensor, transform);
116 else if (IS_CLASS(o, CObservationBeaconRanges))
118 auto beacon = mrpt::ptr_cast<CObservationBeaconRanges>::from(o);
119 mrpt_bridge::convert(*beacon,
msg_beacon_, msg_pose_sensor);
122 std::string childframe =
125 mrpt_bridge::convert(pose_sensor, transform);
131 else if (IS_CLASS(o, CObservationBearingRange))
133 auto landmark = mrpt::ptr_cast<CObservationBearingRange>::from(o);
134 mrpt_bridge::convert(*landmark,
msg_landmark_, msg_pose_sensor);
137 std::string childframe =
140 mrpt_bridge::convert(pose_sensor, transform);
149 "Observation mapping to ROS not implemented: %s",
150 o->GetRuntimeClass()->className);
156 CActionCollection::Ptr
action;
157 CSensoryFrame::Ptr observations;
158 CObservation::Ptr obs;
160 #if MRPT_VERSION >= 0x199 166 if (!CRawlog::getActionObservationPairOrObservation(
167 rs, action, observations, obs,
entry_))
179 mrpt::poses::CPose3DPDFGaussian out_pose_increment;
180 action->getFirstMovementEstimation(out_pose_increment);
201 mrpt_bridge::convert(
robotPose, transform);
int main(int argc, char **argv)
ros::Publisher pub_landmark_
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
RawlogPlayNode(ros::NodeHandle &n)
sensor_msgs::LaserScan msg_laser_
void update(const unsigned long &loop_count)
std::string resolve(const std::string &prefix, const std::string &frame_name)
mrpt::poses::CPose3DPDFGaussian robotPose
nav_msgs::Odometry msg_odom_
void publishSingleObservation(const mrpt::obs::CObservation::Ptr &o)
mrpt_msgs::ObservationRangeBearing msg_landmark_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::TransformBroadcaster tf_broadcaster_
ros::Publisher pub_beacon_
ROSCPP_DECL void spinOnce()
unsigned long loop_count_
mrpt_msgs::ObservationRangeBeacon msg_beacon_
ros::Publisher pub_laser_
CFileGZInputStream rawlog_stream_