Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007 #include <geometry_msgs/Pose.h>
00008 #include "mrpt_bridge/time.h"
00009 #include "mrpt_bridge/pose.h"
00010 #include <mrpt_msgs/ObservationRangeBearing.h>
00011 #include "tf/transform_datatypes.h"
00012 #include "tf/LinearMath/Matrix3x3.h"
00013 #include "mrpt_bridge/landmark.h"
00014
00015 #include <mrpt/version.h>
00016 #include <mrpt/obs/CObservationBearingRange.h>
00017 using namespace mrpt::obs;
00018
00019 namespace mrpt_bridge
00020 {
00021 bool convert(
00022 const mrpt_msgs::ObservationRangeBearing& _msg,
00023 const mrpt::poses::CPose3D& _pose, CObservationBearingRange& _obj)
00024
00025 {
00026
00027 mrpt::poses::CPose3D cpose_obj;
00028
00029
00030
00031 _obj.maxSensorDistance = _msg.max_sensor_distance;
00032 _obj.minSensorDistance = _msg.min_sensor_distance;
00033 _obj.sensor_std_yaw = _msg.sensor_std_yaw;
00034 _obj.sensor_std_pitch = _msg.sensor_std_pitch;
00035 _obj.sensor_std_range = _msg.sensor_std_range;
00036
00037 if (_pose.empty())
00038 {
00039 convert(_msg.sensor_pose_on_robot, cpose_obj);
00040 _obj.setSensorPose(cpose_obj);
00041 }
00042 else
00043 {
00044 _obj.setSensorPose(_pose);
00045 }
00046
00047 ASSERT_(_msg.sensed_data.size() >= 1);
00048 const size_t N = _msg.sensed_data.size();
00049
00050 _obj.sensedData.resize(N);
00051
00052 for (std::size_t i_mrpt = 0; i_mrpt < N; i_mrpt++)
00053 {
00054 _obj.sensedData[i_mrpt].range = _msg.sensed_data[i_mrpt].range;
00055 _obj.sensedData[i_mrpt].landmarkID = _msg.sensed_data[i_mrpt].id;
00056 _obj.sensedData[i_mrpt].yaw = _msg.sensed_data[i_mrpt].yaw;
00057 _obj.sensedData[i_mrpt].pitch = _msg.sensed_data[i_mrpt].pitch;
00058 }
00059 return true;
00060 }
00061
00062 bool convert(
00063 const CObservationBearingRange& _obj,
00064 mrpt_msgs::ObservationRangeBearing& _msg)
00065 {
00066 mrpt::poses::CPose3D cpose_obj;
00067
00068
00069 _obj.getSensorPose(cpose_obj);
00070 convert(cpose_obj, _msg.sensor_pose_on_robot);
00071
00072 _msg.max_sensor_distance = _obj.maxSensorDistance;
00073 _msg.min_sensor_distance = _obj.minSensorDistance;
00074 _msg.sensor_std_yaw = _obj.sensor_std_yaw;
00075 _msg.sensor_std_pitch = _obj.sensor_std_pitch;
00076 _msg.sensor_std_range = _obj.sensor_std_range;
00077
00078 ASSERT_(_obj.sensedData.size() >= 1);
00079 const size_t N = _obj.sensedData.size();
00080
00081 _msg.sensed_data.resize(N);
00082
00083 for (std::size_t i_msg = 0; i_msg < N; i_msg++)
00084 {
00085 _msg.sensed_data[i_msg].range = _obj.sensedData[i_msg].range;
00086 _msg.sensed_data[i_msg].id = _obj.sensedData[i_msg].landmarkID;
00087 _msg.sensed_data[i_msg].yaw = _obj.sensedData[i_msg].yaw;
00088 _msg.sensed_data[i_msg].pitch = _obj.sensedData[i_msg].pitch;
00089 }
00090 return true;
00091 }
00092
00093 bool convert(
00094 const CObservationBearingRange& _obj,
00095 mrpt_msgs::ObservationRangeBearing& _msg, geometry_msgs::Pose& _pose)
00096 {
00097 convert(_obj, _msg);
00098 mrpt::poses::CPose3D pose;
00099 _obj.getSensorPose(pose);
00100 convert(pose, _pose);
00101 return true;
00102 }
00103 }