diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2015-01-04 11:53:31 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2015-01-04 11:53:31 +0100 |
commit | 9c70946bf797a7b3fa3876d0d7a064ed18d9060f (patch) | |
tree | 60fe6985763f32b819cd1b29ece25c6d0b7c5229 /src/modules/mavlink | |
parent | 88022110d005b611d2da73915c5cfa1e308e7090 (diff) | |
parent | 25fc9d791a1faf5d37a6b9a13bd16fafd6a5cf5b (diff) | |
download | px4-firmware-9c70946bf797a7b3fa3876d0d7a064ed18d9060f.tar.gz px4-firmware-9c70946bf797a7b3fa3876d0d7a064ed18d9060f.tar.bz2 px4-firmware-9c70946bf797a7b3fa3876d0d7a064ed18d9060f.zip |
Merge branch 'gps_utc' of github.com:bansiesta/Firmware
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r-- | src/modules/mavlink/mavlink_receiver.cpp | 8 |
1 files changed, 4 insertions, 4 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 1b24b9c52..090b62975 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -369,7 +369,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) /* optical flow */ mavlink_optical_flow_rad_t flow; mavlink_msg_optical_flow_rad_decode(msg, &flow); - + enum Rotation flow_rot; param_get(param_find("SENS_FLOW_ROT"),&flow_rot); @@ -390,8 +390,8 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) f.gyro_temperature = flow.temperature; /* rotate measurements according to parameter */ - float zeroval = 0.0f; - rotate_3f(flow_rot, f.pixel_flow_x_integral, f.pixel_flow_y_integral, zeroval); + float zeroval = 0.0f; + rotate_3f(flow_rot, f.pixel_flow_x_integral, f.pixel_flow_y_integral, zeroval); if (_flow_pub < 0) { _flow_pub = orb_advertise(ORB_ID(optical_flow), &f); @@ -1204,7 +1204,7 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg) memset(&hil_gps, 0, sizeof(hil_gps)); hil_gps.timestamp_time = timestamp; - hil_gps.time_gps_usec = gps.time_usec; + hil_gps.time_utc_usec = gps.time_usec; hil_gps.timestamp_position = timestamp; hil_gps.lat = gps.lat; |