Commit 7ca73ac3 authored by LM's avatar LM

Updated to latest MAVLink v1.0 draft, ported app to API changes

parent 2977b93b
......@@ -394,7 +394,7 @@ void MAVLinkProtocol::sendHeartbeat()
{
if (m_heartbeatsEnabled) {
mavlink_message_t beat;
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL, MAV_FLIGHT_MODE_MANUAL, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL, 0, MAV_STATE_ACTIVE);
sendMessage(beat);
}
if (m_authEnabled) {
......
......@@ -110,9 +110,10 @@ void MAVLinkSimulationLink::run()
{
status.voltage_battery = 0;
status.errors_uart = 0;
status.errors_comm = 0;
system.system_mode = MAV_MODE_PREFLIGHT;
system.base_mode = MAV_MODE_PREFLIGHT;
system.custom_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED;
system.system_status = MAV_STATE_UNINIT;
forever {
......@@ -314,7 +315,7 @@ void MAVLinkSimulationLink::mainloop()
// ATTITUDE
attitude.usec = time;
attitude.time_boot_ms = time/1000;
// Pack message and get size of encoded byte string
mavlink_msg_attitude_encode(systemId, componentId, &msg, &attitude);
// Allocate buffer with packet data
......@@ -324,7 +325,7 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// IMU
rawImuValues.usec = time;
rawImuValues.time_usec = time;
rawImuValues.xmag = 0;
rawImuValues.ymag = 0;
rawImuValues.zmag = 0;
......@@ -402,7 +403,7 @@ void MAVLinkSimulationLink::mainloop()
// streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed, ySpeed, zSpeed, yaw);
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, 0, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed, ySpeed, zSpeed, yaw);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......@@ -456,7 +457,7 @@ void MAVLinkSimulationLink::mainloop()
// STATE
static int statusCounter = 0;
if (statusCounter == 100) {
system.system_mode = (system.system_mode + 1) % MAV_MODE_ENUM_END;
system.base_mode = (system.base_mode + 1) % MAV_MODE_ENUM_END;
statusCounter = 0;
}
statusCounter++;
......@@ -549,7 +550,7 @@ void MAVLinkSimulationLink::mainloop()
typeCounter++;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK, system.system_mode, system.flight_mode, system.system_status, system.safety_status, system.link_status);
messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK, system.base_mode, system.custom_mode, system.system_status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
......@@ -589,7 +590,7 @@ void MAVLinkSimulationLink::mainloop()
// STATUS VEHICLE 2
mavlink_sys_status_t status2;
mavlink_heartbeat_t system2;
system2.system_mode = MAV_MODE_PREFLIGHT;
system2.base_mode = MAV_MODE_PREFLIGHT;
status2.voltage_battery = voltage;
status2.load = 120;
system2.system_status = MAV_STATE_STANDBY;
......@@ -679,12 +680,12 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
mavlink_set_mode_t mode;
mavlink_msg_set_mode_decode(&msg, &mode);
// Set mode indepent of mode.target
system.system_mode = mode.mode;
system.base_mode = mode.base_mode;
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET: {
mavlink_local_position_setpoint_set_t set;
mavlink_msg_local_position_setpoint_set_decode(&msg, &set);
case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT: {
mavlink_set_local_position_setpoint_t set;
mavlink_msg_set_local_position_setpoint_decode(&msg, &set);
spX = set.x;
spY = set.y;
spZ = set.z;
......@@ -843,7 +844,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
readyBufferMutex.unlock();
// Update comm status
status.errors_uart = comm.packet_rx_drop_count;
status.errors_comm = comm.packet_rx_drop_count;
}
......
......@@ -40,7 +40,7 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
nextSPYaw(0.0),
sys_mode(MAV_MODE_PREFLIGHT),
sys_state(MAV_STATE_STANDBY),
nav_mode(MAV_FLIGHT_MODE_PREFLIGHT),
nav_mode(MAV_AUTOPILOT_CUSTOM_MODE_PREFLIGHT),
flying(false),
mavlink_version(version)
{
......@@ -62,13 +62,13 @@ void MAVLinkSimulationMAV::mainloop()
if (flying) {
sys_state = MAV_STATE_ACTIVE;
sys_mode = MAV_MODE_AUTO;
nav_mode = MAV_FLIGHT_MODE_AUTO_MISSION;
nav_mode = MAV_AUTOPILOT_CUSTOM_MODE_AUTO_MISSION;
}
// 1 Hz execution
if (timer1Hz <= 0) {
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_MODE_GUIDED, MAV_FLIGHT_MODE_AUTO_MISSION, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_MODE_GUIDED, MAV_AUTOPILOT_CUSTOM_MODE_AUTO_MISSION, MAV_STATE_ACTIVE);
link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg);
......@@ -142,7 +142,7 @@ void MAVLinkSimulationMAV::mainloop()
// ATTITUDE
mavlink_attitude_t attitude;
attitude.usec = 0;
attitude.time_boot_ms = 0;
attitude.roll = 0.0f;
attitude.pitch = 0.0f;
attitude.yaw = yaw;
......@@ -158,10 +158,10 @@ void MAVLinkSimulationMAV::mainloop()
status.load = 300;
// status.mode = sys_mode;
// status.nav_mode = nav_mode;
status.errors_uart = 0;
status.errors_comm = 0;
status.voltage_battery = 10500;
// status.status = sys_state;
status.battery_percent = 230;
status.battery_remaining = 90;
mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status);
link->sendMAVLinkMessage(&msg);
timer10Hz = 5;
......@@ -196,7 +196,7 @@ void MAVLinkSimulationMAV::mainloop()
pressure.press_diff1 = 2000;
pressure.press_diff2 = 5000;
pressure.temperature = 18150; // 18.15 deg Celsius
pressure.usec = 0; // Works also with zero timestamp
pressure.time_usec = 0; // Works also with zero timestamp
mavlink_msg_raw_pressure_encode(systemid, MAV_COMP_ID_IMU, &msg, &pressure);
link->sendMAVLinkMessage(&msg);
}
......@@ -288,7 +288,7 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
case MAVLINK_MSG_ID_SET_MODE: {
mavlink_set_mode_t mode;
mavlink_msg_set_mode_decode(&msg, &mode);
if (systemid == mode.target) sys_mode = mode.mode;
if (systemid == mode.target_system) sys_mode = mode.base_mode;
}
break;
// FIXME MAVLINKV10PORTINGNEEDED
......@@ -317,11 +317,11 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
// }
// }
break;
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET: {
mavlink_local_position_setpoint_set_t sp;
mavlink_msg_local_position_setpoint_set_decode(&msg, &sp);
case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT: {
mavlink_set_local_position_setpoint_t sp;
mavlink_msg_set_local_position_setpoint_decode(&msg, &sp);
if (sp.target_system == this->systemid) {
nav_mode = MAV_FLIGHT_MODE_AUTO_MISSION;
nav_mode = MAV_AUTOPILOT_CUSTOM_MODE_AUTO_MISSION;
previousSPX = nextSPX;
previousSPY = nextSPY;
previousSPZ = nextSPZ;
......
......@@ -524,7 +524,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq)
mavlink_waypoint_t *cur = waypoints->at(seq);
mavlink_message_t msg;
mavlink_local_position_setpoint_set_t PControlSetPoint;
mavlink_set_local_position_setpoint_t PControlSetPoint;
// send new set point to local IMU
if (cur->frame == 1) {
......@@ -535,7 +535,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq)
PControlSetPoint.z = cur->z;
PControlSetPoint.yaw = cur->param4;
mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint);
mavlink_msg_set_local_position_setpoint_encode(systemid, compid, &msg, &PControlSetPoint);
link->sendMAVLinkMessage(&msg);
......@@ -548,7 +548,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq)
PControlSetPoint.z = cur->z;
PControlSetPoint.yaw = cur->param4;
mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint);
mavlink_msg_set_local_position_setpoint_encode(systemid, compid, &msg, &PControlSetPoint);
link->sendMAVLinkMessage(&msg);
emit messageSent(msg);
}
......
This diff is collapsed.
......@@ -523,8 +523,10 @@ signals:
void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
protected:
/** @brief Get the UNIX timestamp in milliseconds */
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0);
/** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
quint64 getUnixTimeFromMs(quint64 time);
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
quint64 getUnixReferenceTime(quint64 time);
......
......@@ -73,7 +73,7 @@ protected:
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_air_data_t tmpAirData;
#endif
mavlink_gps_raw_t tmpGpsData;
mavlink_gps_raw_int_t tmpGpsData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_date_time_t tmpGpsTime;
#endif
......@@ -155,4 +155,4 @@ private:
};
#endif // SLUGSHILSIM_H
\ No newline at end of file
#endif // SLUGSHILSIM_H
This diff is collapsed.
/** @file
* @brief MAVLink comm protocol testsuite generated from common.xml
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wed Aug 24 17:14:16 2011
*/
#ifndef COMMON_TESTSUITE_H
#define COMMON_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
static void mavtest_generate_outputs(mavlink_channel_t chan)
{
mavlink_msg_heartbeat_send(chan , 5 , 72 , 139 , 206 , 17 , 84 , 151 );
mavlink_msg_sys_status_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 199 , 17963 , 18067 , 18171 , 18275 );
mavlink_msg_system_time_send(chan , 9223372036854775807 , 963497880 );
mavlink_msg_system_time_utc_send(chan , 963497464 , 963497672 );
mavlink_msg_ping_send(chan , 963497880 , 41 , 108 , 9223372036854775807 );
mavlink_msg_change_operator_control_send(chan , 5 , 72 , 139 , "AQGWMCSIYOEUKAQGWMCSIYOEU" );
mavlink_msg_change_operator_control_ack_send(chan , 5 , 72 , 139 );
mavlink_msg_auth_key_send(chan , "ARIZQHYPGXOFWNEVMDULCTKBSJARIZQH" );
mavlink_msg_set_mode_send(chan , 5 , 72 );
mavlink_msg_set_flight_mode_send(chan , 5 , 72 );
mavlink_msg_set_safety_mode_send(chan , 5 , 72 );
mavlink_msg_param_request_read_send(chan , 139 , 206 , "AHOVCJQXELSZGNUB" , 17235 );
mavlink_msg_param_request_list_send(chan , 5 , 72 );
mavlink_msg_param_value_send(chan , "AXUROLIFCZWTQNKH" , 17.0 , 77 , 17443 , 17547 );
mavlink_msg_param_set_send(chan , 17 , 84 , "APETIXMBQFUJYNCR" , 17.0 , 199 );
mavlink_msg_gps_raw_int_send(chan , 9223372036854775807 , 89 , 963497880 , 963498088 , 963498296 , 18275 , 18379 , 18483 , 18587 , 156 );
mavlink_msg_scaled_imu_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 , 18067 , 18171 , 18275 , 18379 , 18483 );
mavlink_msg_gps_status_send(chan , 5 , "72" , "132" , "192" , "252" , "56" );
mavlink_msg_raw_imu_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 , 18067 , 18171 , 18275 , 18379 , 18483 );
mavlink_msg_raw_pressure_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 );
mavlink_msg_scaled_pressure_send(chan , 9223372036854775807 , 73.0 , 101.0 , 18067 );
mavlink_msg_attitude_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 );
mavlink_msg_local_position_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 );
mavlink_msg_global_position_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 );
mavlink_msg_gps_raw_send(chan , 9223372036854775807 , 113 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 , 180 );
mavlink_msg_rc_channels_raw_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 , 53 );
mavlink_msg_rc_channels_scaled_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 , 53 );
mavlink_msg_servo_output_raw_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 );
mavlink_msg_waypoint_send(chan , 223 , 34 , 18691 , 101 , 168 , 235 , 46 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 );
mavlink_msg_waypoint_request_send(chan , 139 , 206 , 17235 );
mavlink_msg_waypoint_set_current_send(chan , 139 , 206 , 17235 );
mavlink_msg_waypoint_current_send(chan , 17235 );
mavlink_msg_waypoint_request_list_send(chan , 5 , 72 );
mavlink_msg_waypoint_count_send(chan , 139 , 206 , 17235 );
mavlink_msg_waypoint_clear_all_send(chan , 5 , 72 );
mavlink_msg_waypoint_reached_send(chan , 17235 );
mavlink_msg_waypoint_ack_send(chan , 5 , 72 , 139 );
mavlink_msg_gps_set_global_origin_send(chan , 41 , 108 , 963497464 , 963497672 , 963497880 );
mavlink_msg_gps_local_origin_set_send(chan , 963497464 , 963497672 , 963497880 );
mavlink_msg_local_position_setpoint_set_send(chan , 53 , 120 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_local_position_setpoint_send(chan , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_global_position_setpoint_int_send(chan , 963497464 , 963497672 , 963497880 , 17859 );
mavlink_msg_safety_set_allowed_area_send(chan , 77 , 144 , 211 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 );
mavlink_msg_safety_allowed_area_send(chan , 77 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 );
mavlink_msg_set_roll_pitch_yaw_thrust_send(chan , 53 , 120 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(chan , 53 , 120 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(chan , 963497464 , 45.0 , 73.0 , 101.0 , 129.0 );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(chan , 963497464 , 45.0 , 73.0 , 101.0 , 129.0 );
mavlink_msg_nav_controller_output_send(chan , 17.0 , 45.0 , 18275 , 18379 , 18483 , 73.0 , 101.0 , 129.0 );
mavlink_msg_position_target_send(chan , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_state_correction_send(chan , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 );
mavlink_msg_request_data_stream_send(chan , 139 , 206 , 17 , 17235 , 84 );
mavlink_msg_data_stream_send(chan , 139 , 17235 , 206 );
mavlink_msg_manual_control_send(chan , 53 , 17.0 , 45.0 , 73.0 , 101.0 , 120 , 187 , 254 , 65 );
mavlink_msg_rc_channels_override_send(chan , 53 , 120 , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 );
mavlink_msg_global_position_int_send(chan , 963497464 , 963497672 , 963497880 , 17859 , 17963 , 18067 , 18171 );
mavlink_msg_vfr_hud_send(chan , 17.0 , 45.0 , 18067 , 18171 , 73.0 , 101.0 );
mavlink_msg_command_short_send(chan , 53 , 120 , 187 , 254 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_command_long_send(chan , 89 , 156 , 223 , 34 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 );
mavlink_msg_command_ack_send(chan , 17.0 , 45.0 );
mavlink_msg_hil_state_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 963499128 , 963499336 , 963499544 , 19523 , 19627 , 19731 , 19835 , 19939 , 20043 );
mavlink_msg_hil_controls_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 , 269.0 , 125 , 192 );
mavlink_msg_hil_rc_inputs_raw_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 , 18067 , 18171 , 18275 , 18379 , 18483 , 18587 , 18691 , 18795 , 101 );
mavlink_msg_optical_flow_send(chan , 9223372036854775807 , 53 , 17859 , 17963 , 120 , 73.0 );
mavlink_msg_memory_vect_send(chan , 17235 , 139 , 206 , "17" );
mavlink_msg_debug_vect_send(chan , "ATMFYRKDWP" , 9223372036854775807 , 73.0 , 101.0 , 129.0 );
mavlink_msg_named_value_float_send(chan , "AHOVCJQXEL" , 17.0 );
mavlink_msg_named_value_int_send(chan , "AHOVCJQXEL" , 963497464 );
mavlink_msg_statustext_send(chan , 5 , "AIQYGOWEMUCKSAIQYGOWEMUCKSAIQYGOWEMUCKSAIQYGOWEMUC" );
mavlink_msg_debug_send(chan , 17 , 17.0 );
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // COMMON_TESTSUITE_H
// MESSAGE BOOT PACKING
#define MAVLINK_MSG_ID_BOOT 1
typedef struct __mavlink_boot_t
{
uint32_t version; ///< The onboard software version
} mavlink_boot_t;
/**
* @brief Pack a boot message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t version)
{
msg->msgid = MAVLINK_MSG_ID_BOOT;
put_uint32_t_by_index(version, 0, msg->payload); // The onboard software version
return mavlink_finalize_message(msg, system_id, component_id, 4, 61);
}
/**
* @brief Pack a boot message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t version)
{
msg->msgid = MAVLINK_MSG_ID_BOOT;
put_uint32_t_by_index(version, 0, msg->payload); // The onboard software version
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 61);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a boot message on a channel and send
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param version The onboard software version
*/
static inline void mavlink_msg_boot_pack_chan_send(mavlink_channel_t chan,
mavlink_message_t* msg,
uint32_t version)
{
msg->msgid = MAVLINK_MSG_ID_BOOT;
put_uint32_t_by_index(version, 0, msg->payload); // The onboard software version
mavlink_finalize_message_chan_send(msg, chan, 4, 61);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Encode a boot struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param boot C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_boot_t* boot)
{
return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version);
}
/**
* @brief Send a boot message
* @param chan MAVLink channel to send the message
*
* @param version The onboard software version
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version)
{
MAVLINK_ALIGNED_MESSAGE(msg, 4);
mavlink_msg_boot_pack_chan_send(chan, msg, version);
}
#endif
// MESSAGE BOOT UNPACKING
/**
* @brief Get field version from boot message
*
* @return The onboard software version
*/
static inline uint32_t mavlink_msg_boot_get_version(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint32_t(msg, 0);
}
/**
* @brief Decode a boot message into a struct
*
* @param msg The message to decode
* @param boot C-struct to decode the message contents into
*/
static inline void mavlink_msg_boot_decode(const mavlink_message_t* msg, mavlink_boot_t* boot)
{
#if MAVLINK_NEED_BYTE_SWAP
boot->version = mavlink_msg_boot_get_version(msg);
#else
memcpy(boot, msg->payload, 4);
#endif
}
// MESSAGE DEBUG PACKING
#define MAVLINK_MSG_ID_DEBUG 255
#define MAVLINK_MSG_ID_DEBUG 254
typedef struct __mavlink_debug_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float value; ///< DEBUG value
uint8_t ind; ///< index of debug variable
} mavlink_debug_t;
#define MAVLINK_MSG_ID_DEBUG_LEN 5
#define MAVLINK_MSG_ID_255_LEN 5
#define MAVLINK_MSG_ID_DEBUG_LEN 9
#define MAVLINK_MSG_ID_254_LEN 9
#define MAVLINK_MESSAGE_INFO_DEBUG { \
"DEBUG", \
2, \
{ { "value", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_debug_t, value) }, \
{ "ind", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_debug_t, ind) }, \
3, \
{ { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \
{ "value", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
{ "ind", MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \
} \
}
......@@ -28,19 +30,21 @@ typedef struct __mavlink_debug_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t ind, float value)
uint32_t time_boot_ms, uint8_t ind, float value)
{
msg->msgid = MAVLINK_MSG_ID_DEBUG;
put_float_by_index(msg, 0, value); // DEBUG value
put_uint8_t_by_index(msg, 4, ind); // index of debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_float_by_index(msg, 4, value); // DEBUG value
put_uint8_t_by_index(msg, 8, ind); // index of debug variable
return mavlink_finalize_message(msg, system_id, component_id, 5, 127);
return mavlink_finalize_message(msg, system_id, component_id, 9, 46);
}
/**
......@@ -49,20 +53,22 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t ind,float value)
uint32_t time_boot_ms,uint8_t ind,float value)
{
msg->msgid = MAVLINK_MSG_ID_DEBUG;
put_float_by_index(msg, 0, value); // DEBUG value
put_uint8_t_by_index(msg, 4, ind); // index of debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_float_by_index(msg, 4, value); // DEBUG value
put_uint8_t_by_index(msg, 8, ind); // index of debug variable
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 127);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 46);
}
/**
......@@ -75,27 +81,29 @@ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t co
*/
static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
{
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value);
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value);
}
/**
* @brief Send a debug message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param ind index of debug variable
* @param value DEBUG value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value)
{
MAVLINK_ALIGNED_MESSAGE(msg, 5);
MAVLINK_ALIGNED_MESSAGE(msg, 9);
msg->msgid = MAVLINK_MSG_ID_DEBUG;
put_float_by_index(msg, 0, value); // DEBUG value
put_uint8_t_by_index(msg, 4, ind); // index of debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_float_by_index(msg, 4, value); // DEBUG value
put_uint8_t_by_index(msg, 8, ind); // index of debug variable
mavlink_finalize_message_chan_send(msg, chan, 5, 127);
mavlink_finalize_message_chan_send(msg, chan, 9, 46);
}
#endif
......@@ -103,6 +111,16 @@ static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, f
// MESSAGE DEBUG UNPACKING
/**
* @brief Get field time_boot_ms from debug message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field ind from debug message
*
......@@ -110,7 +128,7 @@ static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, f
*/
static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint8_t(msg, 4);
return MAVLINK_MSG_RETURN_uint8_t(msg, 8);
}
/**
......@@ -120,7 +138,7 @@ static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
*/
static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 0);
return MAVLINK_MSG_RETURN_float(msg, 4);
}
/**
......@@ -132,9 +150,10 @@ static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
{
#if MAVLINK_NEED_BYTE_SWAP
debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg);
debug->value = mavlink_msg_debug_get_value(msg);
debug->ind = mavlink_msg_debug_get_ind(msg);
#else
memcpy(debug, MAVLINK_PAYLOAD(msg), 5);
memcpy(debug, MAVLINK_PAYLOAD(msg), 9);
#endif
}
// MESSAGE DEBUG_VECT PACKING
#define MAVLINK_MSG_ID_DEBUG_VECT 251
#define MAVLINK_MSG_ID_DEBUG_VECT 250
typedef struct __mavlink_debug_vect_t
{
uint64_t usec; ///< Timestamp
uint64_t time_usec; ///< Timestamp
float x; ///< x
float y; ///< y
float z; ///< z
......@@ -12,14 +12,14 @@ typedef struct __mavlink_debug_vect_t
} mavlink_debug_vect_t;
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_ID_251_LEN 30
#define MAVLINK_MSG_ID_250_LEN 30
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
"DEBUG_VECT", \
5, \
{ { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, usec) }, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ "x", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
{ "y", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
{ "z", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
......@@ -35,24 +35,24 @@ typedef struct __mavlink_debug_vect_t
* @param msg The MAVLink message to compress the data into
*
* @param name Name
* @param usec Timestamp
* @param time_usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, uint64_t usec, float x, float y, float z)
const char *name, uint64_t time_usec, float x, float y, float z)
{
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
put_uint64_t_by_index(msg, 0, usec); // Timestamp
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp
put_float_by_index(msg, 8, x); // x
put_float_by_index(msg, 12, y); // y
put_float_by_index(msg, 16, z); // z
put_char_array_by_index(msg, 20, name, 10); // Name
return mavlink_finalize_message(msg, system_id, component_id, 30, 15);
return mavlink_finalize_message(msg, system_id, component_id, 30, 49);
}
/**
......@@ -62,7 +62,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param name Name
* @param usec Timestamp
* @param time_usec Timestamp
* @param x x
* @param y y
* @param z z
......@@ -70,17 +70,17 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
*/
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,uint64_t usec,float x,float y,float z)
const char *name,uint64_t time_usec,float x,float y,float z)
{
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
put_uint64_t_by_index(msg, 0, usec); // Timestamp
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp
put_float_by_index(msg, 8, x); // x
put_float_by_index(msg, 12, y); // y
put_float_by_index(msg, 16, z); // z
put_char_array_by_index(msg, 20, name, 10); // Name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 15);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49);
}
/**
......@@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8
*/
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
/**
......@@ -101,25 +101,25 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t
* @param chan MAVLink channel to send the message
*
* @param name Name
* @param usec Timestamp
* @param time_usec Timestamp
* @param x x
* @param y y
* @param z z
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t usec, float x, float y, float z)
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z)
{
MAVLINK_ALIGNED_MESSAGE(msg, 30);
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
put_uint64_t_by_index(msg, 0, usec); // Timestamp
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp
put_float_by_index(msg, 8, x); // x
put_float_by_index(msg, 12, y); // y
put_float_by_index(msg, 16, z); // z
put_char_array_by_index(msg, 20, name, 10); // Name
mavlink_finalize_message_chan_send(msg, chan, 30, 15);
mavlink_finalize_message_chan_send(msg, chan, 30, 49);
}
#endif
......@@ -138,11 +138,11 @@ static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t*
}
/**
* @brief Get field usec from debug_vect message
* @brief Get field time_usec from debug_vect message
*
* @return Timestamp
*/
static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
......@@ -186,7 +186,7 @@ static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
#if MAVLINK_NEED_BYTE_SWAP
debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg);
debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
......
// MESSAGE EXTENDED_MESSAGE PACKING
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
typedef struct __mavlink_extended_message_t
{
uint8_t target_system; ///< System which should execute the command
uint8_t target_component; ///< Component which should execute the command, 0 for all components
uint8_t protocol_flags; ///< Retransmission / ACK flags
} mavlink_extended_message_t;
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE_LEN 3
#define MAVLINK_MSG_ID_255_LEN 3
#define MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE { \
"EXTENDED_MESSAGE", \
3, \
{ { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_message_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_message_t, target_component) }, \
{ "protocol_flags", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_extended_message_t, protocol_flags) }, \
} \
}
/**
* @brief Pack a extended_message message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param protocol_flags Retransmission / ACK flags
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_extended_message_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t protocol_flags)
{
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
put_uint8_t_by_index(msg, 0, target_system); // System which should execute the command
put_uint8_t_by_index(msg, 1, target_component); // Component which should execute the command, 0 for all components
put_uint8_t_by_index(msg, 2, protocol_flags); // Retransmission / ACK flags
return mavlink_finalize_message(msg, system_id, component_id, 3, 247);
}
/**
* @brief Pack a extended_message message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param protocol_flags Retransmission / ACK flags
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_extended_message_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint8_t protocol_flags)
{
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
put_uint8_t_by_index(msg, 0, target_system); // System which should execute the command
put_uint8_t_by_index(msg, 1, target_component); // Component which should execute the command, 0 for all components
put_uint8_t_by_index(msg, 2, protocol_flags); // Retransmission / ACK flags
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 247);
}
/**
* @brief Encode a extended_message struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param extended_message C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_extended_message_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_message_t* extended_message)
{
return mavlink_msg_extended_message_pack(system_id, component_id, msg, extended_message->target_system, extended_message->target_component, extended_message->protocol_flags);
}
/**
* @brief Send a extended_message message
* @param chan MAVLink channel to send the message
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param protocol_flags Retransmission / ACK flags
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_extended_message_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t protocol_flags)
{
MAVLINK_ALIGNED_MESSAGE(msg, 3);
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
put_uint8_t_by_index(msg, 0, target_system); // System which should execute the command
put_uint8_t_by_index(msg, 1, target_component); // Component which should execute the command, 0 for all components
put_uint8_t_by_index(msg, 2, protocol_flags); // Retransmission / ACK flags
mavlink_finalize_message_chan_send(msg, chan, 3, 247);
}
#endif
// MESSAGE EXTENDED_MESSAGE UNPACKING
/**
* @brief Get field target_system from extended_message message
*
* @return System which should execute the command
*/
static inline uint8_t mavlink_msg_extended_message_get_target_system(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from extended_message message
*
* @return Component which should execute the command, 0 for all components
*/
static inline uint8_t mavlink_msg_extended_message_get_target_component(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field protocol_flags from extended_message message
*
* @return Retransmission / ACK flags
*/
static inline uint8_t mavlink_msg_extended_message_get_protocol_flags(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a extended_message message into a struct
*
* @param msg The message to decode
* @param extended_message C-struct to decode the message contents into
*/
static inline void mavlink_msg_extended_message_decode(const mavlink_message_t* msg, mavlink_extended_message_t* extended_message)
{
#if MAVLINK_NEED_BYTE_SWAP
extended_message->target_system = mavlink_msg_extended_message_get_target_system(msg);
extended_message->target_component = mavlink_msg_extended_message_get_target_component(msg);
extended_message->protocol_flags = mavlink_msg_extended_message_get_protocol_flags(msg);
#else
memcpy(extended_message, MAVLINK_PAYLOAD(msg), 3);
#endif
}
// MESSAGE GLOBAL_POSITION PACKING
#define MAVLINK_MSG_ID_GLOBAL_POSITION 33
typedef struct __mavlink_global_position_t
{
uint64_t usec; ///< Timestamp (microseconds since unix epoch)
float lat; ///< Latitude, in degrees
float lon; ///< Longitude, in degrees
float alt; ///< Absolute altitude, in meters
float vx; ///< X Speed (in Latitude direction, positive: going north)
float vy; ///< Y Speed (in Longitude direction, positive: going east)
float vz; ///< Z Speed (in Altitude direction, positive: going up)
} mavlink_global_position_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_LEN 32
#define MAVLINK_MSG_ID_33_LEN 32
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION { \
"GLOBAL_POSITION", \
7, \
{ { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \
{ "lat", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \
{ "lon", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \
{ "alt", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \
{ "vx", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \
{ "vy", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \
{ "vz", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \
} \
}
/**
* @brief Pack a global_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since unix epoch)
put_float_by_index(msg, 8, lat); // Latitude, in degrees
put_float_by_index(msg, 12, lon); // Longitude, in degrees
put_float_by_index(msg, 16, alt); // Absolute altitude, in meters
put_float_by_index(msg, 20, vx); // X Speed (in Latitude direction, positive: going north)
put_float_by_index(msg, 24, vy); // Y Speed (in Longitude direction, positive: going east)
put_float_by_index(msg, 28, vz); // Z Speed (in Altitude direction, positive: going up)
return mavlink_finalize_message(msg, system_id, component_id, 32, 147);
}
/**
* @brief Pack a global_position message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float lat,float lon,float alt,float vx,float vy,float vz)
{
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since unix epoch)
put_float_by_index(msg, 8, lat); // Latitude, in degrees
put_float_by_index(msg, 12, lon); // Longitude, in degrees
put_float_by_index(msg, 16, alt); // Absolute altitude, in meters
put_float_by_index(msg, 20, vx); // X Speed (in Latitude direction, positive: going north)
put_float_by_index(msg, 24, vy); // Y Speed (in Longitude direction, positive: going east)
put_float_by_index(msg, 28, vz); // Z Speed (in Altitude direction, positive: going up)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 147);
}
/**
* @brief Encode a global_position struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param global_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
{
return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
}
/**
* @brief Send a global_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
MAVLINK_ALIGNED_MESSAGE(msg, 32);
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since unix epoch)
put_float_by_index(msg, 8, lat); // Latitude, in degrees
put_float_by_index(msg, 12, lon); // Longitude, in degrees
put_float_by_index(msg, 16, alt); // Absolute altitude, in meters
put_float_by_index(msg, 20, vx); // X Speed (in Latitude direction, positive: going north)
put_float_by_index(msg, 24, vy); // Y Speed (in Longitude direction, positive: going east)
put_float_by_index(msg, 28, vz); // Z Speed (in Altitude direction, positive: going up)
mavlink_finalize_message_chan_send(msg, chan, 32, 147);
}
#endif
// MESSAGE GLOBAL_POSITION UNPACKING
/**
* @brief Get field usec from global_position message
*
* @return Timestamp (microseconds since unix epoch)
*/
static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field lat from global_position message
*
* @return Latitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 8);
}
/**
* @brief Get field lon from global_position message
*
* @return Longitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 12);
}
/**
* @brief Get field alt from global_position message
*
* @return Absolute altitude, in meters
*/
static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 16);
}
/**
* @brief Get field vx from global_position message
*
* @return X Speed (in Latitude direction, positive: going north)
*/
static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 20);
}
/**
* @brief Get field vy from global_position message
*
* @return Y Speed (in Longitude direction, positive: going east)
*/
static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 24);
}
/**
* @brief Get field vz from global_position message
*
* @return Z Speed (in Altitude direction, positive: going up)
*/
static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 28);
}
/**
* @brief Decode a global_position message into a struct
*
* @param msg The message to decode
* @param global_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position->usec = mavlink_msg_global_position_get_usec(msg);
global_position->lat = mavlink_msg_global_position_get_lat(msg);
global_position->lon = mavlink_msg_global_position_get_lon(msg);
global_position->alt = mavlink_msg_global_position_get_alt(msg);
global_position->vx = mavlink_msg_global_position_get_vx(msg);
global_position->vy = mavlink_msg_global_position_get_vy(msg);
global_position->vz = mavlink_msg_global_position_get_vz(msg);
#else
memcpy(global_position, MAVLINK_PAYLOAD(msg), 32);
#endif
}
// MESSAGE GPS_LOCAL_ORIGIN_SET PACKING
// MESSAGE GPS_GLOBAL_ORIGIN PACKING
#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET 49
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49
typedef struct __mavlink_gps_local_origin_set_t
typedef struct __mavlink_gps_global_origin_t
{
int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7
int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7
int32_t altitude; ///< Altitude(WGS84), expressed as * 1000
} mavlink_gps_local_origin_set_t;
} mavlink_gps_global_origin_t;
#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET_LEN 12
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
#define MAVLINK_MSG_ID_49_LEN 12
#define MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET { \
"GPS_LOCAL_ORIGIN_SET", \
#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \
"GPS_GLOBAL_ORIGIN", \
3, \
{ { "latitude", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_local_origin_set_t, latitude) }, \
{ "longitude", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_local_origin_set_t, longitude) }, \
{ "altitude", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_local_origin_set_t, altitude) }, \
{ { "latitude", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \
{ "longitude", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \
{ "altitude", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \
} \
}
/**
* @brief Pack a gps_local_origin_set message
* @brief Pack a gps_global_origin message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
......@@ -35,20 +35,20 @@ typedef struct __mavlink_gps_local_origin_set_t
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t latitude, int32_t longitude, int32_t altitude)
{
msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
put_int32_t_by_index(msg, 0, latitude); // Latitude (WGS84), expressed as * 1E7
put_int32_t_by_index(msg, 4, longitude); // Longitude (WGS84), expressed as * 1E7
put_int32_t_by_index(msg, 8, altitude); // Altitude(WGS84), expressed as * 1000
return mavlink_finalize_message(msg, system_id, component_id, 12, 14);
return mavlink_finalize_message(msg, system_id, component_id, 12, 39);
}
/**
* @brief Pack a gps_local_origin_set message on a channel
* @brief Pack a gps_global_origin message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -58,34 +58,34 @@ static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id,
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int32_t latitude,int32_t longitude,int32_t altitude)
{
msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
put_int32_t_by_index(msg, 0, latitude); // Latitude (WGS84), expressed as * 1E7
put_int32_t_by_index(msg, 4, longitude); // Longitude (WGS84), expressed as * 1E7
put_int32_t_by_index(msg, 8, altitude); // Altitude(WGS84), expressed as * 1000
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 14);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 39);
}
/**
* @brief Encode a gps_local_origin_set struct into a message
* @brief Encode a gps_global_origin struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_local_origin_set C-struct to read the message contents from
* @param gps_global_origin C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_local_origin_set_t* gps_local_origin_set)
static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin)
{
return mavlink_msg_gps_local_origin_set_pack(system_id, component_id, msg, gps_local_origin_set->latitude, gps_local_origin_set->longitude, gps_local_origin_set->altitude);
return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude);
}
/**
* @brief Send a gps_local_origin_set message
* @brief Send a gps_global_origin message
* @param chan MAVLink channel to send the message
*
* @param latitude Latitude (WGS84), expressed as * 1E7
......@@ -94,66 +94,66 @@ static inline uint16_t mavlink_msg_gps_local_origin_set_encode(uint8_t system_id
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_local_origin_set_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
{
MAVLINK_ALIGNED_MESSAGE(msg, 12);
msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
put_int32_t_by_index(msg, 0, latitude); // Latitude (WGS84), expressed as * 1E7
put_int32_t_by_index(msg, 4, longitude); // Longitude (WGS84), expressed as * 1E7
put_int32_t_by_index(msg, 8, altitude); // Altitude(WGS84), expressed as * 1000
mavlink_finalize_message_chan_send(msg, chan, 12, 14);
mavlink_finalize_message_chan_send(msg, chan, 12, 39);
}
#endif
// MESSAGE GPS_LOCAL_ORIGIN_SET UNPACKING
// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING
/**
* @brief Get field latitude from gps_local_origin_set message
* @brief Get field latitude from gps_global_origin message
*
* @return Latitude (WGS84), expressed as * 1E7
*/
static inline int32_t mavlink_msg_gps_local_origin_set_get_latitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field longitude from gps_local_origin_set message
* @brief Get field longitude from gps_global_origin message
*
* @return Longitude (WGS84), expressed as * 1E7
*/
static inline int32_t mavlink_msg_gps_local_origin_set_get_longitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field altitude from gps_local_origin_set message
* @brief Get field altitude from gps_global_origin message
*
* @return Altitude(WGS84), expressed as * 1000
*/
static inline int32_t mavlink_msg_gps_local_origin_set_get_altitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_int32_t(msg, 8);
}
/**
* @brief Decode a gps_local_origin_set message into a struct
* @brief Decode a gps_global_origin message into a struct
*
* @param msg The message to decode
* @param gps_local_origin_set C-struct to decode the message contents into
* @param gps_global_origin C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_local_origin_set_decode(const mavlink_message_t* msg, mavlink_gps_local_origin_set_t* gps_local_origin_set)
static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_local_origin_set->latitude = mavlink_msg_gps_local_origin_set_get_latitude(msg);
gps_local_origin_set->longitude = mavlink_msg_gps_local_origin_set_get_longitude(msg);
gps_local_origin_set->altitude = mavlink_msg_gps_local_origin_set_get_altitude(msg);
gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg);
gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg);
gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg);
#else
memcpy(gps_local_origin_set, MAVLINK_PAYLOAD(msg), 12);
memcpy(gps_global_origin, MAVLINK_PAYLOAD(msg), 12);
#endif
}
// MESSAGE GPS_STATUS PACKING
#define MAVLINK_MSG_ID_GPS_STATUS 27
#define MAVLINK_MSG_ID_GPS_STATUS 26
typedef struct __mavlink_gps_status_t
{
......@@ -13,7 +13,7 @@ typedef struct __mavlink_gps_status_t
} mavlink_gps_status_t;
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
#define MAVLINK_MSG_ID_27_LEN 101
#define MAVLINK_MSG_ID_26_LEN 101
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
......
......@@ -4,7 +4,7 @@
typedef struct __mavlink_hil_controls_t
{
uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll_ailerons; ///< Control output -1 .. 1
float pitch_elevator; ///< Control output -1 .. 1
float yaw_rudder; ///< Control output -1 .. 1
......@@ -25,7 +25,7 @@ typedef struct __mavlink_hil_controls_t
#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
"HIL_CONTROLS", \
11, \
{ { "time_us", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_us) }, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
{ "roll_ailerons", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
{ "pitch_elevator", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
{ "yaw_rudder", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
......@@ -46,7 +46,7 @@ typedef struct __mavlink_hil_controls_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
......@@ -60,11 +60,11 @@ typedef struct __mavlink_hil_controls_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
{
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_float_by_index(msg, 8, roll_ailerons); // Control output -1 .. 1
put_float_by_index(msg, 12, pitch_elevator); // Control output -1 .. 1
put_float_by_index(msg, 16, yaw_rudder); // Control output -1 .. 1
......@@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t
put_uint8_t_by_index(msg, 40, mode); // System mode (MAV_MODE)
put_uint8_t_by_index(msg, 41, nav_mode); // Navigation mode (MAV_NAV_MODE)
return mavlink_finalize_message(msg, system_id, component_id, 42, 250);
return mavlink_finalize_message(msg, system_id, component_id, 42, 63);
}
/**
......@@ -85,7 +85,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
......@@ -100,11 +100,11 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t
*/
static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_us,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode)
uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode)
{
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_float_by_index(msg, 8, roll_ailerons); // Control output -1 .. 1
put_float_by_index(msg, 12, pitch_elevator); // Control output -1 .. 1
put_float_by_index(msg, 16, yaw_rudder); // Control output -1 .. 1
......@@ -116,7 +116,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin
put_uint8_t_by_index(msg, 40, mode); // System mode (MAV_MODE)
put_uint8_t_by_index(msg, 41, nav_mode); // Navigation mode (MAV_NAV_MODE)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 250);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 63);
}
/**
......@@ -129,14 +129,14 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin
*/
static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
{
return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_us, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
}
/**
* @brief Send a hil_controls message
* @param chan MAVLink channel to send the message
*
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
......@@ -150,12 +150,12 @@ static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
{
MAVLINK_ALIGNED_MESSAGE(msg, 42);
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_float_by_index(msg, 8, roll_ailerons); // Control output -1 .. 1
put_float_by_index(msg, 12, pitch_elevator); // Control output -1 .. 1
put_float_by_index(msg, 16, yaw_rudder); // Control output -1 .. 1
......@@ -167,7 +167,7 @@ static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_
put_uint8_t_by_index(msg, 40, mode); // System mode (MAV_MODE)
put_uint8_t_by_index(msg, 41, nav_mode); // Navigation mode (MAV_NAV_MODE)
mavlink_finalize_message_chan_send(msg, chan, 42, 250);
mavlink_finalize_message_chan_send(msg, chan, 42, 63);
}
#endif
......@@ -176,11 +176,11 @@ static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_
/**
* @brief Get field time_us from hil_controls message
* @brief Get field time_usec from hil_controls message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_controls_get_time_us(const mavlink_message_t* msg)
static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
......@@ -294,7 +294,7 @@ static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_messag
static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_controls->time_us = mavlink_msg_hil_controls_get_time_us(msg);
hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg);
hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
......
......@@ -4,7 +4,7 @@
typedef struct __mavlink_hil_state_t
{
uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
......@@ -30,7 +30,7 @@ typedef struct __mavlink_hil_state_t
#define MAVLINK_MESSAGE_INFO_HIL_STATE { \
"HIL_STATE", \
16, \
{ { "time_us", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_us) }, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
{ "roll", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
{ "pitch", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
{ "yaw", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
......@@ -56,7 +56,7 @@ typedef struct __mavlink_hil_state_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
......@@ -75,11 +75,11 @@ typedef struct __mavlink_hil_state_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_us, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_float_by_index(msg, 8, roll); // Roll angle (rad)
put_float_by_index(msg, 12, pitch); // Pitch angle (rad)
put_float_by_index(msg, 16, yaw); // Yaw angle (rad)
......@@ -96,7 +96,7 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com
put_int16_t_by_index(msg, 52, yacc); // Y acceleration (mg)
put_int16_t_by_index(msg, 54, zacc); // Z acceleration (mg)
return mavlink_finalize_message(msg, system_id, component_id, 56, 12);
return mavlink_finalize_message(msg, system_id, component_id, 56, 183);
}
/**
......@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
......@@ -125,11 +125,11 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com
*/
static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_us,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc)
uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc)
{
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_float_by_index(msg, 8, roll); // Roll angle (rad)
put_float_by_index(msg, 12, pitch); // Pitch angle (rad)
put_float_by_index(msg, 16, yaw); // Yaw angle (rad)
......@@ -146,7 +146,7 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_
put_int16_t_by_index(msg, 52, yacc); // Y acceleration (mg)
put_int16_t_by_index(msg, 54, zacc); // Z acceleration (mg)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 12);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 183);
}
/**
......@@ -159,14 +159,14 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_
*/
static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
{
return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_us, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
}
/**
* @brief Send a hil_state message
* @param chan MAVLink channel to send the message
*
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
......@@ -185,12 +185,12 @@ static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t c
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_us, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
MAVLINK_ALIGNED_MESSAGE(msg, 56);
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
put_float_by_index(msg, 8, roll); // Roll angle (rad)
put_float_by_index(msg, 12, pitch); // Pitch angle (rad)
put_float_by_index(msg, 16, yaw); // Yaw angle (rad)
......@@ -207,7 +207,7 @@ static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t t
put_int16_t_by_index(msg, 52, yacc); // Y acceleration (mg)
put_int16_t_by_index(msg, 54, zacc); // Z acceleration (mg)
mavlink_finalize_message_chan_send(msg, chan, 56, 12);
mavlink_finalize_message_chan_send(msg, chan, 56, 183);
}
#endif
......@@ -216,11 +216,11 @@ static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t t
/**
* @brief Get field time_us from hil_state message
* @brief Get field time_usec from hil_state message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_state_get_time_us(const mavlink_message_t* msg)
static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
......@@ -384,7 +384,7 @@ static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* ms
static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_state->time_us = mavlink_msg_hil_state_get_time_us(msg);
hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg);
hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
......
// MESSAGE MEMORY_VECT PACKING
#define MAVLINK_MSG_ID_MEMORY_VECT 250
#define MAVLINK_MSG_ID_MEMORY_VECT 249
typedef struct __mavlink_memory_vect_t
{
......@@ -11,7 +11,7 @@ typedef struct __mavlink_memory_vect_t
} mavlink_memory_vect_t;
#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36
#define MAVLINK_MSG_ID_250_LEN 36
#define MAVLINK_MSG_ID_249_LEN 36
#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32
......
// MESSAGE NAMED_VALUE_FLOAT PACKING
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 252
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251
typedef struct __mavlink_named_value_float_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float value; ///< Floating point value
char name[10]; ///< Name of the debug variable
} mavlink_named_value_float_t;
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 14
#define MAVLINK_MSG_ID_252_LEN 14
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18
#define MAVLINK_MSG_ID_251_LEN 18
#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \
"NAMED_VALUE_FLOAT", \
2, \
{ { "value", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_named_value_float_t, value) }, \
{ "name", MAVLINK_TYPE_CHAR, 10, 4, offsetof(mavlink_named_value_float_t, name) }, \
3, \
{ { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \
{ "value", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
{ "name", MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \
} \
}
......@@ -28,19 +30,21 @@ typedef struct __mavlink_named_value_float_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, float value)
uint32_t time_boot_ms, const char *name, float value)
{
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
put_float_by_index(msg, 0, value); // Floating point value
put_char_array_by_index(msg, 4, name, 10); // Name of the debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_float_by_index(msg, 4, value); // Floating point value
put_char_array_by_index(msg, 8, name, 10); // Name of the debug variable
return mavlink_finalize_message(msg, system_id, component_id, 14, 248);
return mavlink_finalize_message(msg, system_id, component_id, 18, 170);
}
/**
......@@ -49,20 +53,22 @@ static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uin
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,float value)
uint32_t time_boot_ms,const char *name,float value)
{
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
put_float_by_index(msg, 0, value); // Floating point value
put_char_array_by_index(msg, 4, name, 10); // Name of the debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_float_by_index(msg, 4, value); // Floating point value
put_char_array_by_index(msg, 8, name, 10); // Name of the debug variable
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 248);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 170);
}
/**
......@@ -75,27 +81,29 @@ static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id
*/
static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
{
return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->name, named_value_float->value);
return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value);
}
/**
* @brief Send a named_value_float message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Floating point value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, const char *name, float value)
static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value)
{
MAVLINK_ALIGNED_MESSAGE(msg, 14);
MAVLINK_ALIGNED_MESSAGE(msg, 18);
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
put_float_by_index(msg, 0, value); // Floating point value
put_char_array_by_index(msg, 4, name, 10); // Name of the debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_float_by_index(msg, 4, value); // Floating point value
put_char_array_by_index(msg, 8, name, 10); // Name of the debug variable
mavlink_finalize_message_chan_send(msg, chan, 14, 248);
mavlink_finalize_message_chan_send(msg, chan, 18, 170);
}
#endif
......@@ -103,6 +111,16 @@ static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, co
// MESSAGE NAMED_VALUE_FLOAT UNPACKING
/**
* @brief Get field time_boot_ms from named_value_float message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field name from named_value_float message
*
......@@ -110,7 +128,7 @@ static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, co
*/
static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name)
{
return MAVLINK_MSG_RETURN_char_array(msg, name, 10, 4);
return MAVLINK_MSG_RETURN_char_array(msg, name, 10, 8);
}
/**
......@@ -120,7 +138,7 @@ static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_mess
*/
static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_float(msg, 0);
return MAVLINK_MSG_RETURN_float(msg, 4);
}
/**
......@@ -132,9 +150,10 @@ static inline float mavlink_msg_named_value_float_get_value(const mavlink_messag
static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float)
{
#if MAVLINK_NEED_BYTE_SWAP
named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg);
named_value_float->value = mavlink_msg_named_value_float_get_value(msg);
mavlink_msg_named_value_float_get_name(msg, named_value_float->name);
#else
memcpy(named_value_float, MAVLINK_PAYLOAD(msg), 14);
memcpy(named_value_float, MAVLINK_PAYLOAD(msg), 18);
#endif
}
// MESSAGE NAMED_VALUE_INT PACKING
#define MAVLINK_MSG_ID_NAMED_VALUE_INT 253
#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252
typedef struct __mavlink_named_value_int_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int32_t value; ///< Signed integer value
char name[10]; ///< Name of the debug variable
} mavlink_named_value_int_t;
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 14
#define MAVLINK_MSG_ID_253_LEN 14
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18
#define MAVLINK_MSG_ID_252_LEN 18
#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \
"NAMED_VALUE_INT", \
2, \
{ { "value", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", MAVLINK_TYPE_CHAR, 10, 4, offsetof(mavlink_named_value_int_t, name) }, \
3, \
{ { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
{ "value", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
} \
}
......@@ -28,19 +30,21 @@ typedef struct __mavlink_named_value_int_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, int32_t value)
uint32_t time_boot_ms, const char *name, int32_t value)
{
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
put_int32_t_by_index(msg, 0, value); // Signed integer value
put_char_array_by_index(msg, 4, name, 10); // Name of the debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_int32_t_by_index(msg, 4, value); // Signed integer value
put_char_array_by_index(msg, 8, name, 10); // Name of the debug variable
return mavlink_finalize_message(msg, system_id, component_id, 14, 63);
return mavlink_finalize_message(msg, system_id, component_id, 18, 44);
}
/**
......@@ -49,20 +53,22 @@ static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,int32_t value)
uint32_t time_boot_ms,const char *name,int32_t value)
{
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
put_int32_t_by_index(msg, 0, value); // Signed integer value
put_char_array_by_index(msg, 4, name, 10); // Name of the debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_int32_t_by_index(msg, 4, value); // Signed integer value
put_char_array_by_index(msg, 8, name, 10); // Name of the debug variable
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 63);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 44);
}
/**
......@@ -75,27 +81,29 @@ static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id,
*/
static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
{
return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->name, named_value_int->value);
return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value);
}
/**
* @brief Send a named_value_int message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Signed integer value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, const char *name, int32_t value)
static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value)
{
MAVLINK_ALIGNED_MESSAGE(msg, 14);
MAVLINK_ALIGNED_MESSAGE(msg, 18);
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
put_int32_t_by_index(msg, 0, value); // Signed integer value
put_char_array_by_index(msg, 4, name, 10); // Name of the debug variable
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot)
put_int32_t_by_index(msg, 4, value); // Signed integer value
put_char_array_by_index(msg, 8, name, 10); // Name of the debug variable
mavlink_finalize_message_chan_send(msg, chan, 14, 63);
mavlink_finalize_message_chan_send(msg, chan, 18, 44);
}
#endif
......@@ -103,6 +111,16 @@ static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, cons
// MESSAGE NAMED_VALUE_INT UNPACKING
/**
* @brief Get field time_boot_ms from named_value_int message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field name from named_value_int message
*
......@@ -110,7 +128,7 @@ static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, cons
*/
static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name)
{
return MAVLINK_MSG_RETURN_char_array(msg, name, 10, 4);
return MAVLINK_MSG_RETURN_char_array(msg, name, 10, 8);
}
/**
......@@ -120,7 +138,7 @@ static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_messag
*/
static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_int32_t(msg, 0);
return MAVLINK_MSG_RETURN_int32_t(msg, 4);
}
/**
......@@ -132,9 +150,10 @@ static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_messag
static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int)
{
#if MAVLINK_NEED_BYTE_SWAP
named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg);
named_value_int->value = mavlink_msg_named_value_int_get_value(msg);
mavlink_msg_named_value_int_get_name(msg, named_value_int->name);
#else
memcpy(named_value_int, MAVLINK_PAYLOAD(msg), 14);
memcpy(named_value_int, MAVLINK_PAYLOAD(msg), 18);
#endif
}
......@@ -4,7 +4,7 @@
typedef struct __mavlink_optical_flow_t
{
uint64_t time; ///< Timestamp (UNIX)
uint64_t time_usec; ///< Timestamp (UNIX)
float ground_distance; ///< Ground distance in meters
int16_t flow_x; ///< Flow in pixels in x-sensor direction
int16_t flow_y; ///< Flow in pixels in y-sensor direction
......@@ -20,7 +20,7 @@ typedef struct __mavlink_optical_flow_t
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
"OPTICAL_FLOW", \
6, \
{ { "time", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time) }, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "ground_distance", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "flow_x", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_optical_flow_t, flow_x) }, \
{ "flow_y", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_optical_flow_t, flow_y) }, \
......@@ -36,7 +36,7 @@ typedef struct __mavlink_optical_flow_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time Timestamp (UNIX)
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
......@@ -45,18 +45,18 @@ typedef struct __mavlink_optical_flow_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
{
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
put_uint64_t_by_index(msg, 0, time); // Timestamp (UNIX)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (UNIX)
put_float_by_index(msg, 8, ground_distance); // Ground distance in meters
put_int16_t_by_index(msg, 12, flow_x); // Flow in pixels in x-sensor direction
put_int16_t_by_index(msg, 14, flow_y); // Flow in pixels in y-sensor direction
put_uint8_t_by_index(msg, 16, sensor_id); // Sensor ID
put_uint8_t_by_index(msg, 17, quality); // Optical flow quality / confidence. 0: bad, 255: maximum quality
return mavlink_finalize_message(msg, system_id, component_id, 18, 146);
return mavlink_finalize_message(msg, system_id, component_id, 18, 19);
}
/**
......@@ -65,7 +65,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time Timestamp (UNIX)
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
......@@ -75,18 +75,18 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
*/
static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,uint8_t quality,float ground_distance)
uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,uint8_t quality,float ground_distance)
{
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
put_uint64_t_by_index(msg, 0, time); // Timestamp (UNIX)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (UNIX)
put_float_by_index(msg, 8, ground_distance); // Ground distance in meters
put_int16_t_by_index(msg, 12, flow_x); // Flow in pixels in x-sensor direction
put_int16_t_by_index(msg, 14, flow_y); // Flow in pixels in y-sensor direction
put_uint8_t_by_index(msg, 16, sensor_id); // Sensor ID
put_uint8_t_by_index(msg, 17, quality); // Optical flow quality / confidence. 0: bad, 255: maximum quality
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 146);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 19);
}
/**
......@@ -99,14 +99,14 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
*/
static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
{
return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance);
return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance);
}
/**
* @brief Send a optical_flow message
* @param chan MAVLink channel to send the message
*
* @param time Timestamp (UNIX)
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
......@@ -115,19 +115,19 @@ static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
{
MAVLINK_ALIGNED_MESSAGE(msg, 18);
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
put_uint64_t_by_index(msg, 0, time); // Timestamp (UNIX)
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp (UNIX)
put_float_by_index(msg, 8, ground_distance); // Ground distance in meters
put_int16_t_by_index(msg, 12, flow_x); // Flow in pixels in x-sensor direction
put_int16_t_by_index(msg, 14, flow_y); // Flow in pixels in y-sensor direction
put_uint8_t_by_index(msg, 16, sensor_id); // Sensor ID
put_uint8_t_by_index(msg, 17, quality); // Optical flow quality / confidence. 0: bad, 255: maximum quality
mavlink_finalize_message_chan_send(msg, chan, 18, 146);
mavlink_finalize_message_chan_send(msg, chan, 18, 19);
}
#endif
......@@ -136,11 +136,11 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
/**
* @brief Get field time from optical_flow message
* @brief Get field time_usec from optical_flow message
*
* @return Timestamp (UNIX)
*/
static inline uint64_t mavlink_msg_optical_flow_get_time(const mavlink_message_t* msg)
static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
......@@ -204,7 +204,7 @@ static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_m
static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow)
{
#if MAVLINK_NEED_BYTE_SWAP
optical_flow->time = mavlink_msg_optical_flow_get_time(msg);
optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg);
optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg);
optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg);
optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
......
......@@ -4,7 +4,7 @@
typedef struct __mavlink_ping_t
{
uint64_t time; ///< Unix timestamp in microseconds
uint64_t time_usec; ///< Unix timestamp in microseconds
uint32_t seq; ///< PING sequence
uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
......@@ -18,7 +18,7 @@ typedef struct __mavlink_ping_t
#define MAVLINK_MESSAGE_INFO_PING { \
"PING", \
4, \
{ { "time", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time) }, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \
{ "seq", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \
{ "target_system", MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \
......@@ -32,23 +32,23 @@ typedef struct __mavlink_ping_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Unix timestamp in microseconds
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component)
{
msg->msgid = MAVLINK_MSG_ID_PING;
put_uint64_t_by_index(msg, 0, time); // Unix timestamp in microseconds
put_uint64_t_by_index(msg, 0, time_usec); // Unix timestamp in microseconds
put_uint32_t_by_index(msg, 8, seq); // PING sequence
put_uint8_t_by_index(msg, 12, target_system); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
put_uint8_t_by_index(msg, 13, target_component); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
return mavlink_finalize_message(msg, system_id, component_id, 14, 105);
return mavlink_finalize_message(msg, system_id, component_id, 14, 237);
}
/**
......@@ -57,24 +57,24 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Unix timestamp in microseconds
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t seq,uint8_t target_system,uint8_t target_component,uint64_t time)
uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component)
{
msg->msgid = MAVLINK_MSG_ID_PING;
put_uint64_t_by_index(msg, 0, time); // Unix timestamp in microseconds
put_uint64_t_by_index(msg, 0, time_usec); // Unix timestamp in microseconds
put_uint32_t_by_index(msg, 8, seq); // PING sequence
put_uint8_t_by_index(msg, 12, target_system); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
put_uint8_t_by_index(msg, 13, target_component); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 105);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 237);
}
/**
......@@ -87,31 +87,31 @@ static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t com
*/
static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
{
return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time);
return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component);
}
/**
* @brief Send a ping message
* @param chan MAVLink channel to send the message
*
* @param time_usec Unix timestamp in microseconds
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component)
{
MAVLINK_ALIGNED_MESSAGE(msg, 14);
msg->msgid = MAVLINK_MSG_ID_PING;
put_uint64_t_by_index(msg, 0, time); // Unix timestamp in microseconds
put_uint64_t_by_index(msg, 0, time_usec); // Unix timestamp in microseconds
put_uint32_t_by_index(msg, 8, seq); // PING sequence
put_uint8_t_by_index(msg, 12, target_system); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
put_uint8_t_by_index(msg, 13, target_component); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
mavlink_finalize_message_chan_send(msg, chan, 14, 105);
mavlink_finalize_message_chan_send(msg, chan, 14, 237);
}
#endif
......@@ -119,6 +119,16 @@ static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, u
// MESSAGE PING UNPACKING
/**
* @brief Get field time_usec from ping message
*
* @return Unix timestamp in microseconds
*/
static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field seq from ping message
*
......@@ -149,16 +159,6 @@ static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_messag
return MAVLINK_MSG_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field time from ping message
*
* @return Unix timestamp in microseconds
*/
static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg)
{
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
/**
* @brief Decode a ping message into a struct
*
......@@ -168,7 +168,7 @@ static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg)
static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping)
{
#if MAVLINK_NEED_BYTE_SWAP
ping->time = mavlink_msg_ping_get_time(msg);
ping->time_usec = mavlink_msg_ping_get_time_usec(msg);
ping->seq = mavlink_msg_ping_get_seq(msg);
ping->target_system = mavlink_msg_ping_get_target_system(msg);
ping->target_component = mavlink_msg_ping_get_target_component(msg);
......
// MESSAGE SAFETY_ALLOWED_AREA PACKING
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 54
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55
typedef struct __mavlink_safety_allowed_area_t
{
......@@ -14,7 +14,7 @@ typedef struct __mavlink_safety_allowed_area_t
} mavlink_safety_allowed_area_t;
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25
#define MAVLINK_MSG_ID_54_LEN 25
#define MAVLINK_MSG_ID_55_LEN 25
......
// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING
#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 53
#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54
typedef struct __mavlink_safety_set_allowed_area_t
{
......@@ -16,7 +16,7 @@ typedef struct __mavlink_safety_set_allowed_area_t
} mavlink_safety_set_allowed_area_t;
#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27
#define MAVLINK_MSG_ID_53_LEN 27
#define MAVLINK_MSG_ID_54_LEN 27
......
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Aug 29 10:37:55 2011"
#define MAVLINK_BUILD_DATE "Mon Aug 29 12:10:51 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment