Merge release_v1.0.0 into master

This commit is contained in:
Lorenz Meier 2015-05-28 18:08:31 -07:00
commit c62ae87c69
2 changed files with 8 additions and 5 deletions

View File

@ -361,11 +361,14 @@ GPS::task_main()
_report_gps_pos.timestamp_variance = hrt_absolute_time(); _report_gps_pos.timestamp_variance = hrt_absolute_time();
_report_gps_pos.timestamp_velocity = hrt_absolute_time(); _report_gps_pos.timestamp_velocity = hrt_absolute_time();
_report_gps_pos.timestamp_time = hrt_absolute_time(); _report_gps_pos.timestamp_time = hrt_absolute_time();
if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else { if (!(_pub_blocked)) {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos); if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
} }
// GPS is obviously detected successfully, reset statistics // GPS is obviously detected successfully, reset statistics

View File

@ -1007,7 +1007,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
* which makes the corner positions unreachable. * which makes the corner positions unreachable.
* scale yaw up and clip it to overcome this. * scale yaw up and clip it to overcome this.
*/ */
rc.values[2] = man.r / 1.5f + 1500; rc.values[2] = man.r / 1.2f + 1500;
if (rc.values[2] > 2000) { if (rc.values[2] > 2000) {
rc.values[2] = 2000; rc.values[2] = 2000;
} else if (rc.values[2] < 1000) { } else if (rc.values[2] < 1000) {