aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-11-20 22:34:15 +0100
committerJulian Oes <julian@oes.ch>2013-11-20 22:34:15 +0100
commitb3c657450056eab9ec1549b80a4cf4c002d1503b (patch)
tree007b74255fe0d12492d3701b93061068a84b3956 /src/modules
parentf351afe3f69c81e4f1ee43f24531728e4b518cea (diff)
downloadpx4-firmware-b3c657450056eab9ec1549b80a4cf4c002d1503b.tar.gz
px4-firmware-b3c657450056eab9ec1549b80a4cf4c002d1503b.tar.bz2
px4-firmware-b3c657450056eab9ec1549b80a4cf4c002d1503b.zip
Waypoints: Get time inside WP radius right
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/mavlink/waypoints.c4
-rw-r--r--src/modules/uORB/topics/mission.h2
2 files changed, 3 insertions, 3 deletions
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index 5fdbd57e1..964adee1d 100644
--- a/src/modules/mavlink/waypoints.c
+++ b/src/modules/mavlink/waypoints.c
@@ -76,7 +76,7 @@ void map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavl
mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
mission_item->nav_cmd = NAV_CMD_WAYPOINT; // TODO correct
mission_item->radius = mavlink_mission_item->param1;
- mission_item->time_inside = mavlink_mission_item->param2;
+ mission_item->time_inside = mavlink_mission_item->param2 / 1e3f; /* from milliseconds to seconds */
}
void map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, const uint16_t seq, mavlink_mission_item_t *mavlink_mission_item)
@@ -89,7 +89,7 @@ void map_mission_item_to_mavlink_mission_item(const struct mission_item_s *missi
mavlink_mission_item->param3 = mission_item->loiter_radius*(float)mission_item->loiter_direction;
mavlink_mission_item->command = MAV_CMD_NAV_WAYPOINT; // TODO add
mavlink_mission_item->param1 = mission_item->radius;
- mavlink_mission_item->param2 = mission_item->time_inside;
+ mavlink_mission_item->param2 = mission_item->time_inside * 1e3f; /* from seconds to milliseconds */
mavlink_mission_item->seq = seq;
}
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index ec7835279..4c251269b 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -78,7 +78,7 @@ struct mission_item_s
int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
float radius; /**< radius in which the mission is accepted as reached in meters */
- float time_inside; /**< time that the MAV should stay inside the radius before advancing in milliseconds */
+ float time_inside; /**< time that the MAV should stay inside the radius before advancing in seconds */
};
struct mission_s