26 bool ros2mrpt(
const sensor_msgs::Range& msg, CObservationRange& obj)
28 obj.minSensorDistance = msg.min_range;
29 obj.maxSensorDistance = msg.max_range;
30 obj.sensorConeApperture = msg.field_of_view;
34 obj.sensedData.at(0).sensedDistance = msg.range;
43 sensor_msgs::Range* msg)
45 long num_range = obj.sensedData.size();
48 for (
int i = 0; i < num_range; i++) msg[i].
header = msg_header;
51 for (
int i = 0; i < num_range; i++)
53 msg[i].max_range = obj.maxSensorDistance;
54 msg[i].min_range = obj.minSensorDistance;
55 msg[i].field_of_view = obj.sensorConeApperture;
61 for (
int i = 0; i < num_range; i++)
62 msg[i].range = obj.sensedData.at(i).sensedDistance;