From a318d0cf40057ee22e792518c1011b6128e3535a Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 19 Nov 2013 11:44:41 +0100 Subject: fix off by one in missionlib --- src/modules/mavlink/missionlib.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src/modules/mavlink/missionlib.c') diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c index fa23f996f..bb857dc69 100644 --- a/src/modules/mavlink/missionlib.c +++ b/src/modules/mavlink/missionlib.c @@ -276,7 +276,7 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, next_setpoint_index = index + 1; } - while (next_setpoint_index < wpm->size - 1) { + while (next_setpoint_index < wpm->size) { if (wpm->waypoints[next_setpoint_index].frame == (int)MAV_FRAME_GLOBAL && (wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_WAYPOINT || wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TURNS || -- cgit v1.2.3 From a9e51105c81a4de0cf35a03af0be67fb49ba8870 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 19 Nov 2013 16:15:16 +0100 Subject: Missionlib: Don't let the missionlib publish the triplet, moving forward this should be done by the navigator --- src/modules/mavlink/missionlib.c | 84 ++++++++++++++++++++-------------------- 1 file changed, 42 insertions(+), 42 deletions(-) (limited to 'src/modules/mavlink/missionlib.c') diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c index fa23f996f..9b1d3c51a 100644 --- a/src/modules/mavlink/missionlib.c +++ b/src/modules/mavlink/missionlib.c @@ -206,7 +206,7 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command) { static orb_advert_t global_position_setpoint_pub = -1; - static orb_advert_t global_position_set_triplet_pub = -1; + // static orb_advert_t global_position_set_triplet_pub = -1; static orb_advert_t local_position_setpoint_pub = -1; static unsigned last_waypoint_index = -1; char buf[50] = {0}; @@ -234,10 +234,10 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, /* fill triplet: previous, current, next waypoint */ - struct vehicle_global_position_set_triplet_s triplet; + // struct vehicle_global_position_set_triplet_s triplet; /* current waypoint is same as sp */ - memcpy(&(triplet.current), &sp, sizeof(sp)); + // memcpy(&(triplet.current), &sp, sizeof(sp)); /* * Check if previous WP (in mission, not in execution order) @@ -291,48 +291,48 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, /* populate last and next */ - triplet.previous_valid = false; - triplet.next_valid = false; - - if (last_setpoint_valid) { - triplet.previous_valid = true; - struct vehicle_global_position_setpoint_s sp; - sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f; - sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f; - sp.altitude = wpm->waypoints[last_setpoint_index].z; - sp.altitude_is_relative = false; - sp.yaw = (wpm->waypoints[last_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F; - set_special_fields(wpm->waypoints[last_setpoint_index].param1, - wpm->waypoints[last_setpoint_index].param2, - wpm->waypoints[last_setpoint_index].param3, - wpm->waypoints[last_setpoint_index].param4, - wpm->waypoints[last_setpoint_index].command, &sp); - memcpy(&(triplet.previous), &sp, sizeof(sp)); - } - - if (next_setpoint_valid) { - triplet.next_valid = true; - struct vehicle_global_position_setpoint_s sp; - sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f; - sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f; - sp.altitude = wpm->waypoints[next_setpoint_index].z; - sp.altitude_is_relative = false; - sp.yaw = (wpm->waypoints[next_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F; - set_special_fields(wpm->waypoints[next_setpoint_index].param1, - wpm->waypoints[next_setpoint_index].param2, - wpm->waypoints[next_setpoint_index].param3, - wpm->waypoints[next_setpoint_index].param4, - wpm->waypoints[next_setpoint_index].command, &sp); - memcpy(&(triplet.next), &sp, sizeof(sp)); - } + // triplet.previous_valid = false; + // triplet.next_valid = false; + + // if (last_setpoint_valid) { + // triplet.previous_valid = true; + // struct vehicle_global_position_setpoint_s sp; + // sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f; + // sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f; + // sp.altitude = wpm->waypoints[last_setpoint_index].z; + // sp.altitude_is_relative = false; + // sp.yaw = (wpm->waypoints[last_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F; + // set_special_fields(wpm->waypoints[last_setpoint_index].param1, + // wpm->waypoints[last_setpoint_index].param2, + // wpm->waypoints[last_setpoint_index].param3, + // wpm->waypoints[last_setpoint_index].param4, + // wpm->waypoints[last_setpoint_index].command, &sp); + // memcpy(&(triplet.previous), &sp, sizeof(sp)); + // } + + // if (next_setpoint_valid) { + // triplet.next_valid = true; + // struct vehicle_global_position_setpoint_s sp; + // sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f; + // sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f; + // sp.altitude = wpm->waypoints[next_setpoint_index].z; + // sp.altitude_is_relative = false; + // sp.yaw = (wpm->waypoints[next_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F; + // set_special_fields(wpm->waypoints[next_setpoint_index].param1, + // wpm->waypoints[next_setpoint_index].param2, + // wpm->waypoints[next_setpoint_index].param3, + // wpm->waypoints[next_setpoint_index].param4, + // wpm->waypoints[next_setpoint_index].command, &sp); + // memcpy(&(triplet.next), &sp, sizeof(sp)); + // } /* Initialize triplet publication if necessary */ - if (global_position_set_triplet_pub < 0) { - global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet); + // if (global_position_set_triplet_pub < 0) { + // global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet); - } else { - orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet); - } + // } else { + // orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet); + // } sprintf(buf, "[mp] WP#%i lat: % 3.6f/lon % 3.6f/alt % 4.6f/hdg %3.4f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4); -- cgit v1.2.3 From 5c85fa2c5f4bf1b9d8fe12043f56ebc7dbe53d13 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 26 Dec 2013 15:16:32 +0100 Subject: Missionlib: deactivate functions now implemented in navigator --- src/modules/mavlink/missionlib.c | 9 +++++++++ 1 file changed, 9 insertions(+) (limited to 'src/modules/mavlink/missionlib.c') diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c index 5845429db..318dcf08c 100644 --- a/src/modules/mavlink/missionlib.c +++ b/src/modules/mavlink/missionlib.c @@ -73,11 +73,15 @@ #include "waypoints.h" #include "mavlink_parameters.h" + + static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN]; static uint64_t loiter_start_time; +#if 0 static bool set_special_fields(float param1, float param2, float param3, float param4, uint16_t command, struct vehicle_global_position_setpoint_s *sp); +#endif int mavlink_missionlib_send_message(mavlink_message_t *msg) @@ -88,6 +92,8 @@ mavlink_missionlib_send_message(mavlink_message_t *msg) return 0; } + + int mavlink_missionlib_send_gcs_string(const char *string) { @@ -127,6 +133,7 @@ uint64_t mavlink_missionlib_get_system_timestamp() return hrt_absolute_time(); } +#if 0 /** * Set special vehicle setpoint fields based on current mission item. * @@ -388,3 +395,5 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, printf("%s\n", buf); //printf("[mavlink mp] new setpoint\n");//: frame: %d, lat: %d, lon: %d, alt: %d, yaw: %d\n", frame, param5_lat_x*1000, param6_lon_y*1000, param7_alt_z*1000, param4*1000); } + +#endif \ No newline at end of file -- cgit v1.2.3