floatparam1;///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
floatparam2;///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
floatparam3;///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
floatparam4;///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
floatx;///< PARAM5 / local: x position, global: latitude
floaty;///< PARAM6 / y position: global: longitude
p->target_system=target_system;// uint8_t:System ID
p->target_component=target_component;// uint8_t:Component ID
p->seq=seq;// uint16_t:Sequence
p->frame=frame;// uint8_t:The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
p->command=command;// uint8_t:The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
p->current=current;// uint8_t:false:0, true:1
p->autocontinue=autocontinue;// uint8_t:autocontinue to next wp
p->param1=param1;// float:PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
p->param2=param2;// float:PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
p->param3=param3;// float:PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
p->param4=param4;// float:PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
p->x=x;// float:PARAM5 / local: x position, global: latitude
p->y=y;// float:PARAM6 / y position: global: longitude
p->z=z;// float:PARAM7 / z position: global: altitude
p->target_system=target_system;// uint8_t:System ID
p->target_component=target_component;// uint8_t:Component ID
p->seq=seq;// uint16_t:Sequence
p->frame=frame;// uint8_t:The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
p->command=command;// uint8_t:The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
p->current=current;// uint8_t:false:0, true:1
p->autocontinue=autocontinue;// uint8_t:autocontinue to next wp
p->param1=param1;// float:PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
p->param2=param2;// float:PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
p->param3=param3;// float:PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
p->param4=param4;// float:PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
p->x=x;// float:PARAM5 / local: x position, global: latitude
p->y=y;// float:PARAM6 / y position: global: longitude
p->z=z;// float:PARAM7 / z position: global: altitude
p->target_system=target_system;// uint8_t:System ID
p->target_component=target_component;// uint8_t:Component ID
p->seq=seq;// uint16_t:Sequence
p->frame=frame;// uint8_t:The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
p->command=command;// uint8_t:The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
p->current=current;// uint8_t:false:0, true:1
p->autocontinue=autocontinue;// uint8_t:autocontinue to next wp
p->param1=param1;// float:PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
p->param2=param2;// float:PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
p->param3=param3;// float:PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
p->param4=param4;// float:PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
p->x=x;// float:PARAM5 / local: x position, global: latitude
p->y=y;// float:PARAM6 / y position: global: longitude
p->z=z;// float:PARAM7 / z position: global: altitude