@ -258,7 +258,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
{
mavlink_raw_imu_t raw ;
mavlink_raw_imu_t raw ;
mavlink_msg_raw_imu_decode ( & message , & raw ) ;
mavlink_msg_raw_imu_decode ( & message , & raw ) ;
quint64 time = getUnixTime ( raw . m sec) ;
quint64 time = getUnixTime ( raw . u sec) ;
emit valueChanged ( uasId , " Accel. X " , raw . xacc , time ) ;
emit valueChanged ( uasId , " Accel. X " , raw . xacc , time ) ;
emit valueChanged ( uasId , " Accel. Y " , raw . yacc , time ) ;
emit valueChanged ( uasId , " Accel. Y " , raw . yacc , time ) ;
@ -330,12 +330,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
positionLock = true ;
positionLock = true ;
}
}
break ;
break ;
case MAVLINK_MSG_ID_POSITION :
case MAVLINK_MSG_ID_LOCAL_ POSITION :
//std::cerr << std::endl;
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
{
{
mavlink_position_t pos ;
mavlink_local_ position_t pos ;
mavlink_msg_position_decode ( & message , & pos ) ;
mavlink_msg_local_ position_decode ( & message , & pos ) ;
quint64 time = getUnixTime ( pos . usec ) ;
quint64 time = getUnixTime ( pos . usec ) ;
emit valueChanged ( uasId , " x " , pos . x , time ) ;
emit valueChanged ( uasId , " x " , pos . x , time ) ;
emit valueChanged ( uasId , " y " , pos . y , time ) ;
emit valueChanged ( uasId , " y " , pos . y , time ) ;
@ -346,6 +346,38 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit localPositionChanged ( this , pos . x , pos . y , pos . z , time ) ;
emit localPositionChanged ( this , pos . x , pos . y , pos . z , time ) ;
}
}
break ;
break ;
case MAVLINK_MSG_ID_GLOBAL_POSITION :
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
{
mavlink_global_position_t pos ;
mavlink_msg_global_position_decode ( & message , & pos ) ;
quint64 time = getUnixTime ( pos . usec ) ;
emit valueChanged ( uasId , " lat " , pos . lat , time ) ;
emit valueChanged ( uasId , " lon " , pos . lon , time ) ;
emit valueChanged ( uasId , " alt " , pos . alt , time ) ;
emit valueChanged ( uasId , " g-vx " , pos . vx , time ) ;
emit valueChanged ( uasId , " g-vy " , pos . vy , time ) ;
emit valueChanged ( uasId , " g-vz " , pos . vz , time ) ;
emit globalPositionChanged ( this , pos . lon , pos . lat , pos . alt , time ) ;
}
break ;
case MAVLINK_MSG_ID_GPS_RAW :
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
{
mavlink_gps_raw_t pos ;
mavlink_msg_gps_raw_decode ( & message , & pos ) ;
quint64 time = getUnixTime ( pos . usec ) ;
emit valueChanged ( uasId , " lat " , pos . lat , time ) ;
emit valueChanged ( uasId , " lon " , pos . lon , time ) ;
emit valueChanged ( uasId , " alt " , pos . alt , time ) ;
emit valueChanged ( uasId , " g-vx " , pos . vx , time ) ;
emit valueChanged ( uasId , " g-vy " , pos . vy , time ) ;
emit valueChanged ( uasId , " g-vz " , pos . vz , time ) ;
emit globalPositionChanged ( this , pos . lon , pos . lat , pos . alt , time ) ;
}
break ;
case MAVLINK_MSG_ID_PARAM_VALUE :
case MAVLINK_MSG_ID_PARAM_VALUE :
{
{
mavlink_param_value_t value ;
mavlink_param_value_t value ;