diff --git a/files/parameter_tooltips/MAV_AUTOPILOT_ARDUPILOTMEGA-MAV_TYPE_FIXED_WING.txt b/files/ardupilotmega/fixed_wing/parameter_tooltips/tooltips.txt similarity index 100% rename from files/parameter_tooltips/MAV_AUTOPILOT_ARDUPILOTMEGA-MAV_TYPE_FIXED_WING.txt rename to files/ardupilotmega/fixed_wing/parameter_tooltips/tooltips.txt diff --git a/files/ardupilotmega/quadrotor/parameter_tooltips/tooltips.txt b/files/ardupilotmega/quadrotor/parameter_tooltips/tooltips.txt new file mode 100644 index 0000000000000000000000000000000000000000..6b8ca0735d8290d6f51c69a99f63796348572a20 --- /dev/null +++ b/files/ardupilotmega/quadrotor/parameter_tooltips/tooltips.txt @@ -0,0 +1,216 @@ +== MAVLink Parameters == +|| *EEPROM variable name* || *Min* || *Max* || *Default* || *Multiplier* || *Enabled (0 = no, 1 = yes)* || *Comment* || +||MAH|| || ||1|| || || || +||CURRENT_ENABLE|| || ||1|| || || || +||AOA|| || ||1|| || || || +||MAG_ENABLE|| || ||1|| || || || +||HDNG2RLL_P||0||5||0.7||1||1||NAV_ROLL_P - Navigation control gains. Tuning values for the navigation control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||HDNG2RLL_I||0||1||0.01||1||1||NAV_ROLL_I - Navigation control gains. Tuning values for the navigation control PID loops. The I term is used to control drift.|| +||HDNG2RLL_D||0||1||0.02||1||1||NAV_ROLL_D - Navigation control gains. Tuning values for the navigation control PID loops. The D term is used to control overshoot. Avoid adjusting this term if you are not familiar with tuning PID loops.|| +||HDNG2RLL_IMAX||0||3000||500||100||1||NAV_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. native flight AoA). If you find this value is insufficient consider adjusting the AOA parameter.|| +||RLL2SRV_P||0||5||0.4||1||1||SERVO_ROLL_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||RLL2SRV_I||0||1||0||1||1||SERVO_ROLL_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| +||RLL2SRV_D||0||1||0||1||1||SERVO_ROLL_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| +||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||PTCH2SRV_P||0||5||0.6||1||1||SERVO_PITCH_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||PTCH2SRV_I||0||1||0||1||1||SERVO_PITCH_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| +||PTCH2SRV_D||0||1||0||1||1||SERVO_PITCH_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| +||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||ARSPD2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ASP_P - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_I||0||1||0||1||1||NAV_PITCH_ASP_I - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_D||0||1||0||1||1||NAV_PITCH_ASP_D - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX_CMSEC - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).|| +||YW2SRV_P||0||5||0||1||1||SERVO_YAW_P - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_I||0||1||0||1||1||SERVO_YAW_I - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_D||0||1||0||1||1||SERVO_YAW_D - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_IMAX||0||3000||0||100||1||SERVO_YAW_INT_MAX - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking).|| +||ENRGY2THR_P||0||5||0.5||1||1||THROTTLE_TE_P - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_I||0||1||0||1||1||THROTTLE_TE_I - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_D||0||1||0||1||1||THROTTLE_TE_D - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_IMAX||0||100||20||1||1||THROTTLE_TE_INT_MAX - In Percent - Maximum throttle input due to the integral term. This limits the throttle from being overdriven due to a persistent offset (e.g. inability to maintain the programmed altitude).|| +||ALT2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ALT_P - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_I||0||1||0||1||1||NAV_PITCH_ALT_I - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_D||0||1||0||1||1||NAV_PITCH_ALT_D - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX_CM - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).|| +||KFF_PTCHCOMP||-3||3||0.2||0.01||1||PITCH_COMP - In Percent - Adds pitch input to compensate for the loss of lift due to roll control.|| +||KFF_RDDRMIX||-3||3||0.5||0.01||1||RUDDER_MIX - Roll to yaw mixing. This allows for co-ordinated turns.|| +||KFF_PTCH2THR||-3||3||0||1||1||P_TO_T - Pitch to throttle feed-forward gain.|| +||KFF_THR2PTCH||-3||3||0||1||1||T_TO_P - Throttle to pitch feed-forward gain.|| +||XTRK_GAIN_SC||0||100||100||100||1||XTRACK_GAIN_SCALED - Default value is 1.0 degrees per metre. Values lower than 0.001 will disable crosstrack compensation.|| +||ALT_MIX||0||1||1||0.01||1||ALTITUDE_MIX - In Percent - Configures the blend between GPS and pressure altitude. 0 = GPS altitude, 1 = Press alt, 0.5 = half and half, etc.|| +||ARSPD_RATIO||0||5||1.9936||1||1||AIRSPEED_RATIO - Adjust AIRSPEED_RATIO in small increments to calibrate the airspeed sensor relative to your GPS. The calculation and default value are optimized for speeds around 12 m/s|| +||WP_RADIUS||0||200||30||1||1||WP_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the waypoint radius (the radius from a target waypoint within which the APM will consider itself to have arrived at the waypoint) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||WP_LOITER_RAD||0||200||60||1||1||LOITER_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the loiter radius (the distance the APM will attempt to maintain from a waypoint while loitering) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||ARSPD_FBW_MIN||5||50||6||1||1||AIRSPEED_FBW_MIN - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode.|| +||ARSPD_FBW_MAX||5||50||22||1||1||AIRSPEED_FBW_MAX - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode. AIRSPEED_FBW_MAX also sets the maximum airspeed that the cruise airspeed can be ""nudged"" to in AUTO mode when ENABLE_STICK_MIXING is set. In AUTO the cruise airspeed can be increased between AIRSPEED_CRUISE and AIRSPEED_FBW_MAX by positioning the throttle stick in the top 1/2 of its range. Throttle stick in the bottom 1/2 provide regular AUTO control.|| +||THR_MIN||0||100||0||1||1||THROTTLE_MIN - The minimum throttle setting to which the autopilot will reduce the throttle while descending. The default is zero, which is suitable for aircraft with a steady power-off glide. Increase this value if your aircraft needs throttle to maintain a stable descent in level flight.|| +||THR_MAX||0||100||75||1||1||THROTTLE_MAX - The maximum throttle setting the autopilot will apply. The default is 75%. Reduce this value if your aicraft is overpowered or has complex flight characteristics at high throttle settings.|| +||THR_FAILSAFE||0||0||1|| || ||THROTTLE_FAILSAFE - The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel (channel 3). This can be used to achieve a failsafe override on loss of radio control without having to sacrifice one of your FLIGHT_MODE settings as the throttle failsafe overrides the switch-selected mode. Throttle failsafe is enabled by setting THROTTLE_FAILSAFE to 1.|| +||THR_FS_ACTION||0||2||1||1|| ||THROTTLE_FAILSAFE_ACTION - The FAILSAFE_ACTION setting determines what APM will do when throttle failsafe mode is entered while flying in AUTO mode. This is important in order to avoid accidental failsafe behaviour when flying waypoints that take the aircraft temporarily out of radio range. If FAILSAFE_ACTION is 1 when failsafe is entered in AUTO or LOITER modes the aircraft will head for home in RTL mode. If the throttle channel moves back up it will return to AUTO or LOITER mode. The default behavior is to ignore throttle failsafe in AUTO and LOITER modes.|| +||TRIM_THROTTLE||0||90||45||1||1||THROTTLE_CRUISE - In Percent - The approximate throttle setting to achieve AIRSPEED_CRUISE in level flight. The default is 45% which is reasonable for a modestly powered aircraft.|| +||TRIM_AUTO||0||1||1||1||1||AUTO_TRIM - !ArduPilot Mega can update its trim settings by looking at the radio inputs when switching out of MANUAL mode. This allows you to manually trim your aircraft before switching to an assisted mode but it also means that you should avoid switching out of MANUAL while you have any control stick deflection.|| +||FLTMODE_CH||5||8||8||1||1||FLIGHT_MODE_CHANNEL - Flight modes assigned to the control channel, and the input channel that is read for the control mode. Use a servo tester or the !ArduPilotMega_demo test program to check your switch settings. ATTENTION: Some !ArduPilot Mega boards have radio channels marked 0-7 and others have them marked the standard 1-8. The FLIGHT_MODE_CHANNEL option uses channel numbers 1-8 (and defaults to 8). If you only have a three-position switch or just want three modes set your switch to produce 1165, 1425, and 1815 microseconds and configure FLIGHT_MODE 1 & 2, 3 & 4 and 5 & 6 to be the same. This is the default. If you have FLIGHT_MODE_CHANNEL set to 8 (the default) and your control channel connected to input channel 8, the hardware failsafe mode will activate for any control input over 1750ms.|| +||FLIGHT_MODE_1||0||14||11||1|| ||FLIGHT_MODE_1 - The following standard flight modes are available: MANUAL = Full manual control via the hardware multiplexer. STABILIZE = Tries to maintain level flight but can be overridden with radio control inputs. FLY_BY_WIRE_A = Autopilot style control via user input with manual throttle. FLY_BY_WIRE_B = Autopilot style control via user input, aispeed controlled with throttle. RTL = Returns to the Home location and then LOITERs at a safe altitude. AUTO = Autonomous flight based on programmed waypoints.|| +||FLIGHT_MODE_2||0||14||11||1|| ||FLIGHT_MODE_2|| +||FLIGHT_MODE_3||0||14||5||1|| ||FLIGHT_MODE_3|| +||FLIGHT_MODE_4||0||14||5||1|| ||FLIGHT_MODE_4|| +||FLIGHT_MODE_5||0||14||0||1|| ||FLIGHT_MODE_5|| +||FLIGHT_MODE_6||0||14||0||1|| ||FLIGHT_MODE_6|| +||RC1_MIN||900||2100||1500||1||1||PWM_RC1_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC1_MAX||900||2100||1500||1||1||PWM_RC1_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC1_TRIM||900||2100||1200||1||1||PWM_RC1_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_MIN||900||2100||1500||1||1||PWM_RC2_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_MAX||900||2100||1500||1||1||PWM_RC2_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_TRIM||900||2100||1200||1||1||PWM_RC2_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC3_MIN||900||2100||1500||1||1||PWM_RC3_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC3_MAX||900||2100||1500||1||1||PWM_RC3_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC3_TRIM||900||2100||1500||1||1||PWM_RC3_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_MIN||900||2100||1500||1||1||PWM_RC4_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_MAX||900||2100||1500||1||1||PWM_RC4_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_TRIM||900||2100||1200||1||1||PWM_RC4_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MIN||900||2100||1500||1||1||PWM_CH5_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_TRIM||900||2100||1500||1||1||PWM_CH5_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_MIN||900||2100||1500||1||1||PWM_CH6_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_MAX||900||2100||1500||1||1||PWM_CH6_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_TRIM||900||2100||1500||1||1||PWM_CH6_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_MIN||900||2100||1500||1||1||PWM_CH7_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_MAX||900||2100||1500||1||1||PWM_CH7_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_TRIM||900||2100||1500||1||1||PWM_CH7_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_MIN||900||2100||1500||1||1||PWM_CH8_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_MAX||900||2100||1500||1||1||PWM_CH8_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_TRIM||900||2100||1500||1||1||PWM_CH8_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||IMU_OFFSET_0||0||0||0|| || ||IMU_OFFSET_0 - IMU Calibration|| +||IMU_OFFSET_1||0||0||0|| || ||IMU_OFFSET_1 - IMU Calibration|| +||IMU_OFFSET_2||0||0||0|| || ||IMU_OFFSET_2 - IMU Calibration|| +||IMU_OFFSET_3||0||0||0|| || ||IMU_OFFSET_3 - IMU Calibration|| +||IMU_OFFSET_4||0||0||0|| || ||IMU_OFFSET_4 - IMU Calibration|| +||IMU_OFFSET_5||0||0||0|| || ||IMU_OFFSET_5 - IMU Calibration|| +||YAW_MODE|| || ||0|| || ||YAW_MODE|| +||WP_MODE|| || ||0|| || ||WP_MODE|| +||WP_TOTAL||0||255|| ||0|| ||WP_TOTAL|| +||WP_INDEX||0||255|| ||0|| ||WP_INDEX|| +||CONFIG|| || ||1|| || ||CONFIG_OPTIONS|| +||SWITCH_ENABLE||0||1||1||1||1||REVERS_SWITCH_ENABLE - 0 = Off, 1 = On, Enables/Disables physical reverse switches on APM board|| +||FIRMWARE_VER|| || ||0|| || ||FIRMWARE_VER|| +||LOG_BITMASK||0||65535||334||1||1||LOG_BITMASK|| +||TRIM_ELEVON||900||2100||1500||1||1||TRIM_ELEVON|| +||THR_FS_VALUE||850||1000||950||1||1||THROTTLE_FS_VALUE - If the throttle failsafe is enabled, THROTTLE_FS_VALUE sets the channel value below which the failsafe engages. The default is 975ms, which is a very low throttle setting. Most transmitters will let you trim the manual throttle position up so that you cannot engage the failsafe with a regular stick movement. Configure your receiver's failsafe setting for the throttle channel to the absolute minimum, and use the !ArduPilotMega_demo program to check that you cannot reach that value with the throttle control. Leave a margin of at least 50 microseconds between the lowest throttle setting and THROTTLE_FS_VALUE.|| +||TRIM_ARSPD_CM||500||5000||1200||100||1||AIRSPEED_CRUISE_CM - The speed in metres per second to maintain during cruise. The default is 10m/s, which is a conservative value suitable for relatively small, light aircraft.|| +||GND_TEMP||-10||50||28||1||1||GND_TEMP - Ground Temperature|| +||AP_OFFSET|| || ||0|| || ||AP_OFFSET|| +||TRIM_PITCH_CD|| || ||0|| || ||TRIM_PITCH_CD|| +||ALT_HOLD_RTL||0||20000||10000||100||1||ALT_HOLD_HOME_CM - When the user performs a factory reset on the APM. Sets the flag for weather the current altitude or ALT_HOLD_HOME altitude should be used for Return To Launch. Also sets the value of USE_CURRENT_ALT in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_CENTIDEGREE - Maximum angle used to correct for track following.|| +||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_CENTIDEGREE|| +||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_CENTIDEGREE|| +||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_CENTIDEGREE|| +||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_CENTIDEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.|| +||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_CENTIDEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall|| +||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_CENTIDEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.|| +||GND_ALT_CM||0||500000||0||100||1||GND_ALT_CM|| +||GND_ABS_PRESS|| || ||0|| || ||GND_ABS_PRESS|| +||COMPASS_DEC||-1.57075||1.57075||0||1|| ||COMPASS_DEC - Compass Declination|| +||SR0_EXT_STAT||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS|| +||SR0_EXTRA1||0||50||10||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_ATTITUDE|| +||SR0_EXTRA2||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_VFR_HUD|| +||SR0_EXTRA3||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Not currently used|| +||SR0_POSITION||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages|| +||SR0_RAW_CTRL||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT|| +||SR0_RAW_SENS||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets|| +||SR0_RC_CHAN||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW|| +||SR3_EXT_STAT||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS|| +||SR3_EXTRA1||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_ATTITUDE|| +||SR3_EXTRA2||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_VFR_HUD|| +||SR3_EXTRA3||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Not currently used|| +||SR3_POSITION||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages|| +||SR3_RAW_CTRL||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT|| +||SR3_RAW_SENS||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets|| +||SR3_RC_CHAN||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW|| +||MAG_ENABLE||0||1||0||1||1||MAG_ENABLE - 0 = Off, 1 = On, Magnetometer Enable|| +||ARSPD_ENABLE||0||1||0||1||1||AIRSPEED_ENABLE - 0 = Off, 1 = On, Airspeed Sensor Enable|| +||BATT_CAPACITY||0||10000||1760||1||1||BATTERY_MAH - Battery capacity in mAh|| +||BATT_MONITOR||0||4||0||1||1||BATTERY_MONITOR - The value should be set to 0 to disable battery monitoring, 1 to measure cell voltages for a 3 cell lipo, 2 to measure cell voltages for a 4 cell lipo, 3 to measure the total battery voltage (only) on input 1, or 4 to measure total battery voltage on input 1 and current on input 2. || +||FS_GCS_ENABL||0||1||0||1||1||FS_GCS_ENABLE - 0 = Off, 1 = On, If the GCS heartbeat is lost for 20 seconds, the plane will Return to Launch|| +||FS_LONG_ACTN||0||1||0||1||1||FS_LONG_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 20 srconds, the plane will Return to Launch|| +||FS_SHORT_ACTN||0||1||0||1||1||FS_SHORT_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 1.5 seconds, the plane will circle until heartbeat is found again or 20 seconds has passed|| +||SYSID_MYGCS||0||255||255||1||1||SYSID_MYGCS - The system ID of the GCS|| +||SYSID_THISMAV||0||255||1||1||1||SYSID_THISMAV - The system ID of the MAVlink vehicle|| +||AOA|| || ||0|| || +||ACR_PIT_D|| || ||1|| || ||Description coming soon|| +||ACR_PIT_I|| || ||1|| || ||Description coming soon|| +||ACR_PIT_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_PIT_P|| || ||1|| || ||Description coming soon|| +||ACR_RLL_D|| || ||1|| || ||Description coming soon|| +||ACR_RLL_I|| || ||1|| || ||Description coming soon|| +||ACR_RLL_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_RLL_P|| || ||1|| || ||Description coming soon|| +||ACR_YAW_D|| || ||1|| || ||Description coming soon|| +||ACR_YAW_I|| || ||1|| || ||Description coming soon|| +||ACR_YAW_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_YAW_P|| || ||1|| || ||Description coming soon|| +||ESC|| || ||1|| || ||ESC_CALIBRATE_MODE|| +||FRAME|| || ||1|| || ||FRAME_ORIENTATION || +||LOITER_RADIUS|| || ||1|| || ||Description coming soon|| +||NAV_LAT_D|| || ||1|| || ||Description coming soon|| +||NAV_LAT_I|| || ||1|| || ||Description coming soon|| +||NAV_LAT_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_LAT_P|| || ||1|| || ||Description coming soon|| +||NAV_LON_D|| || ||1|| || ||Description coming soon|| +||NAV_LON_I|| || ||1|| || ||Description coming soon|| +||NAV_LON_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_LON_P|| || ||1|| || ||Description coming soon|| +||NAV_WP_D|| || ||1|| || ||Description coming soon|| +||NAV_WP_I|| || ||1|| || ||Description coming soon|| +||NAV_WP_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_WP_P|| || ||1|| || ||Description coming soon|| +||PITCH_MAX|| || ||1|| || ||Description coming soon|| +||SONAR_ENABLE||0||1||0||1||1||SONAR_ENABLE - 0 = Off, 1 = On, Sonar Enable|| +||STB_PIT_D|| || ||1|| || ||Description coming soon|| +||STB_PIT_I|| || ||1|| || ||Description coming soon|| +||STB_PIT_IMAX|| || ||1|| || ||Description coming soon|| +||STB_PIT_P|| || ||1|| || ||Description coming soon|| +||STB_RLL_D|| || ||1|| || ||Description coming soon|| +||STB_RLL_I|| || ||1|| || ||Description coming soon|| +||STB_RLL_IMAX|| || ||1|| || ||Description coming soon|| +||STB_RLL_P|| || ||1|| || ||Description coming soon|| +||STB_YAW_D|| || ||1|| || ||Description coming soon|| +||STB_YAW_I|| || ||1|| || ||Description coming soon|| +||STB_YAW_IMAX|| || ||1|| || ||Description coming soon|| +||STB_YAW_P|| || ||1|| || ||Description coming soon|| +||THR_BAR_D|| || ||1|| || ||Description coming soon|| +||THR_BAR_I|| || ||1|| || ||Description coming soon|| +||THR_BAR_IMAX|| || ||1|| || ||Description coming soon|| +||THR_BAR_P|| || ||1|| || ||Description coming soo|| +||THR_SON_D|| || ||1|| || ||Description coming soon|| +||THR_SON_I|| || ||1|| || ||Description coming soon|| +||THR_SON_IMAX|| || ||1|| || ||Description coming soon|| +||THR_SON_P|| || ||1|| || ||Description coming soon|| +||WP_MODE|| || ||1|| || ||Description coming soon|| +||WP_MUST_INDEX|| || ||1|| || ||Description coming soon|| +||XTRACK_ANGLE|| || ||1|| || ||Description coming soon|| +||XTRK_GAIN|| || ||1|| || ||Description coming soon|| +||ARSPD_OFFSET|| || ||0|| || ||Description coming soon|| +||ELEVON_CH1_REV||0||1||0||1||1||ELEVON_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||ELEVON_CH2_REV||0||1||0||1||1||ELEVON_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||ELEVON_MIXING||0||1||0||1||1||ELEVON_MIXING - 0 = Disabled, 1 = Enabled|| +||ELEVON_REVERSE||0||1||0||1||1||ELEVON_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||INVERTEDFLT_CH||0||8||0||1||1||INVERTED_FLIGHT_CHANNEL - Channel to select inverted flight mode, 0 = Disabled|| +||RC1_REV||0||1||1||1||1||RC_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC2_REV||0||1||1||1||1||RC_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC3_REV||0||1||1||1||1||RC_CHANNEL3_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC4_REV||0||1||1||1||1||RC_CHANNEL4_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC5_REV||0||1||1||1||1||RC_CHANNEL5_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC6_REV||0||1||1||1||1||RC_CHANNEL6_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC7_REV||0||1||1||1||1||RC_CHANNEL7_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC8_REV||0||1||1||1||1||RC_CHANNEL8_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||SYSID_SW_MREV|| || ||0|| || ||Description coming soon|| +||SYSID_SW_TYPE|| || ||0|| || ||Description coming soon|| +||THR_SLEWRATE||0||100||0||1||1||THROTTLE_SLEW_RATE - 0 = Disabled, otherwise it limits throttle movement rate. Units are % per second. This is a test feature and may go away.|| +||FLTMODE1||0||20||1||1|| ||FLIGHT_MODE_1 - Mode switch setting 1 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL|| +||FLTMODE2||0||20||1||1|| ||FLIGHT_MODE_2 - Mode switch setting 2 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL|| +||FLTMODE3||0||20||1||1|| ||FLIGHT_MODE_3 - Mode switch setting 3 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL|| +||FLTMODE4||0||20||1||1|| ||FLIGHT_MODE_4 - Mode switch setting 4 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL|| +||FLTMODE5||0||20||1||1|| ||FLIGHT_MODE_5 - Mode switch setting 5 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL|| +||FLTMODE6||0||20||1||1|| ||FLIGHT_MODE_6 - Mode switch setting 6 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL|| \ No newline at end of file diff --git a/files/mavlink_generator/mavgen_c.py b/files/mavlink_generator/mavgen_c.py new file mode 100644 index 0000000000000000000000000000000000000000..68e56cfc10b4d9a267ab59da1f6a57d1c25333e1 --- /dev/null +++ b/files/mavlink_generator/mavgen_c.py @@ -0,0 +1,550 @@ +#!/usr/bin/env python +''' +parse a MAVLink protocol XML file and generate a C implementation + +Copyright Andrew Tridgell 2011 +Released under GNU GPL version 3 or later +''' + +import sys, textwrap, os, time +import mavparse, mavtemplate + +t = mavtemplate.MAVTemplate() + +def generate_version_h(directory, xml): + '''generate version.h''' + f = open(os.path.join(directory, "version.h"), mode='w') + t.write(f,''' +/** @file + * @brief MAVLink comm protocol built from ${basename}.xml + * @see http://pixhawk.ethz.ch/software/mavlink + */ +#ifndef MAVLINK_VERSION_H +#define MAVLINK_VERSION_H + +#define MAVLINK_BUILD_DATE "${parse_time}" +#define MAVLINK_WIRE_PROTOCOL_VERSION "${wire_protocol_version}" +#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE ${largest_payload} + +#endif // MAVLINK_VERSION_H +''', xml) + f.close() + +def generate_mavlink_h(directory, xml): + '''generate mavlink.h''' + f = open(os.path.join(directory, "mavlink.h"), mode='w') + t.write(f,''' +/** @file + * @brief MAVLink comm protocol built from ${basename}.xml + * @see http://pixhawk.ethz.ch/software/mavlink + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#ifndef MAVLINK_STX +#define MAVLINK_STX ${protocol_marker} +#endif + +#ifndef MAVLINK_ENDIAN +#define MAVLINK_ENDIAN ${mavlink_endian} +#endif + +#ifndef MAVLINK_ALIGNED_FIELDS +#define MAVLINK_ALIGNED_FIELDS ${aligned_fields_define} +#endif + +#ifndef MAVLINK_CRC_EXTRA +#define MAVLINK_CRC_EXTRA ${crc_extra_define} +#endif + +#include "version.h" +#include "${basename}.h" + +#endif // MAVLINK_H +''', xml) + f.close() + +def generate_main_h(directory, xml): + '''generate main header per XML file''' + f = open(os.path.join(directory, xml.basename + ".h"), mode='w') + t.write(f, ''' +/** @file + * @brief MAVLink comm protocol generated from ${basename}.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef ${basename_upper}_H +#define ${basename_upper}_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {${message_lengths_array}} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {${message_crcs_array}} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {${message_info_array}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_${basename_upper} + +${{include_list:#include "../${base}/${base}.h" +}} + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION ${version} +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION ${version} +#endif + +// ENUM DEFINITIONS + +${{enum: +/** @brief ${description} */ +enum ${name} +{ +${{entry: ${name}=${value}, /* ${description} |${{param:${description}| }} */ +}} +}; +}} + +// MESSAGE DEFINITIONS +${{message:#include "./mavlink_msg_${name_lower}.h" +}} + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // ${basename_upper}_H +''', xml) + + f.close() + + +def generate_message_h(directory, m): + '''generate per-message header for a XML file''' + f = open(os.path.join(directory, 'mavlink_msg_%s.h' % m.name_lower), mode='w') + t.write(f, ''' +// MESSAGE ${name} PACKING + +#define MAVLINK_MSG_ID_${name} ${id} + +typedef struct __mavlink_${name_lower}_t +{ +${{ordered_fields: ${type} ${name}${array_suffix}; ///< ${description} +}} +} mavlink_${name_lower}_t; + +#define MAVLINK_MSG_ID_${name}_LEN ${wire_length} +#define MAVLINK_MSG_ID_${id}_LEN ${wire_length} + +${{array_fields:#define MAVLINK_MSG_${msg_name}_FIELD_${name_upper}_LEN ${array_length} +}} + +#define MAVLINK_MESSAGE_INFO_${name} { \\ + "${name}", \\ + ${num_fields}, \\ + { ${{ordered_fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\ + }} } \\ +} + + +/** + * @brief Pack a ${name_lower} 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 + * +${{arg_fields: * @param ${name} ${description} +}} + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[${wire_length}]; +${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname}); +}} +${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); +}} + memcpy(_MAV_PAYLOAD(msg), buf, ${wire_length}); +#else + mavlink_${name_lower}_t packet; +${{scalar_fields: packet.${name} = ${putname}; +}} +${{array_fields: memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); +}} + memcpy(_MAV_PAYLOAD(msg), &packet, ${wire_length}); +#endif + + msg->msgid = MAVLINK_MSG_ID_${name}; + return mavlink_finalize_message(msg, system_id, component_id, ${wire_length}${crc_extra_arg}); +} + +/** + * @brief Pack a ${name_lower} 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 +${{arg_fields: * @param ${name} ${description} +}} + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + ${{arg_fields:${array_const}${type} ${array_prefix}${name},}}) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[${wire_length}]; +${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname}); +}} +${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); +}} + memcpy(_MAV_PAYLOAD(msg), buf, ${wire_length}); +#else + mavlink_${name_lower}_t packet; +${{scalar_fields: packet.${name} = ${putname}; +}} +${{array_fields: memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); +}} + memcpy(_MAV_PAYLOAD(msg), &packet, ${wire_length}); +#endif + + msg->msgid = MAVLINK_MSG_ID_${name}; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, ${wire_length}${crc_extra_arg}); +} + +/** + * @brief Encode a ${name_lower} 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 ${name_lower} C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_${name_lower}_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower}) +{ + return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}}); +} + +/** + * @brief Send a ${name_lower} message + * @param chan MAVLink channel to send the message + * +${{arg_fields: * @param ${name} ${description} +}} + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[${wire_length}]; +${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname}); +}} +${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); +}} + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, ${wire_length}${crc_extra_arg}); +#else + mavlink_${name_lower}_t packet; +${{scalar_fields: packet.${name} = ${putname}; +}} +${{array_fields: memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); +}} + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)&packet, ${wire_length}${crc_extra_arg}); +#endif +} + +#endif + +// MESSAGE ${name} UNPACKING + +${{fields: +/** + * @brief Get field ${name} from ${name_lower} message + * + * @return ${description} + */ +static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg}) +{ + return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset}); +} +}} + +/** + * @brief Decode a ${name_lower} message into a struct + * + * @param msg The message to decode + * @param ${name_lower} C-struct to decode the message contents into + */ +static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower}) +{ +#if MAVLINK_NEED_BYTE_SWAP +${{ordered_fields: ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right}); +}} +#else + memcpy(${name_lower}, _MAV_PAYLOAD(msg), ${wire_length}); +#endif +} +''', m) + f.close() + + +def generate_testsuite_h(directory, xml): + '''generate testsuite.h per XML file''' + f = open(os.path.join(directory, "testsuite.h"), mode='w') + t.write(f, ''' +/** @file + * @brief MAVLink comm protocol testsuite generated from ${basename}.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef ${basename_upper}_TESTSUITE_H +#define ${basename_upper}_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +${{include_list:static void mavlink_test_${base}(uint8_t, uint8_t, mavlink_message_t *last_msg); +}} +static void mavlink_test_${basename}(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ +${{include_list: mavlink_test_${base}(system_id, component_id, last_msg); +}} + mavlink_test_${basename}(system_id, component_id, last_msg); +} +#endif + +${{include_list:#include "../${base}/testsuite.h" +}} + +${{message: +static void mavlink_test_${name_lower}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_${name_lower}_t packet_in = { + ${{ordered_fields:${c_test_value}, + }}}; + mavlink_${name_lower}_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + ${{scalar_fields: packet1.${name} = packet_in.${name}; + }} + ${{array_fields: memcpy(packet1.${name}, packet_in.${name}, sizeof(${type})*${array_length}); + }} + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_${name_lower}_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_${name_lower}_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_${name_lower}_pack(system_id, component_id, &msg ${{arg_fields:, packet1.${name} }}); + mavlink_msg_${name_lower}_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_${name_lower}_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg ${{arg_fields:, packet1.${name} }}); + mavlink_msg_${name_lower}_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i= 1 and self.buf[0] != ${protocol_marker}: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + if self.callback: + self.callback(m, *self.callback_args, **self.callback_kwargs) + self.expected_length = 6 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = self.buf[0:self.expected_length] + self.buf = self.buf[self.expected_length:] + self.expected_length = 6 + if self.robust_parsing: + try: + m = self.decode(mbuf) + self.total_packets_received += 1 + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + self.total_packets_received += 1 + if self.callback: + self.callback(m, *self.callback_args, **self.callback_kwargs) + return m + return None + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != ${protocol_marker}: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + (fmt, type, order_map, crc_extra) = mavlink_map[msgId] + + # decode the checksum + try: + crc, = struct.unpack(' 64: + raise MAVParseError("num_fields=%u : Maximum number of field names allowed is" % ( + m.num_fields, 64)) + m.crc_extra = message_checksum(m) + self.message_lengths[m.id] = m.wire_length + self.message_names[m.id] = m.name + self.message_crcs[m.id] = m.crc_extra + if m.wire_length > self.largest_payload: + self.largest_payload = m.wire_length + + if m.wire_length+8 > 64: + print("Warning: message %s is longer than 64 bytes long (%u bytes)" % (m.name, m.wire_length+8)) + + + def __str__(self): + return "MAVXML for %s from %s (%u message, %u enums)" % ( + self.basename, self.filename, len(self.message), len(self.enum)) + + +def message_checksum(msg): + '''calculate a 8-bit checksum of the key fields of a message, so we + can detect incompatible XML changes''' + crc = mavutil.x25crc(msg.name + ' ') + for f in msg.ordered_fields: + crc.accumulate(f.type + ' ') + crc.accumulate(f.name + ' ') + if f.array_length: + crc.accumulate(chr(f.array_length)) + return (crc.crc&0xFF) ^ (crc.crc>>8) + +def check_duplicates(xml): + '''check for duplicate message IDs''' + msgmap = {} + for x in xml: + for m in x.message: + if m.id in msgmap: + print("ERROR: Duplicate message id %u for %s (%s:%u) also used by %s" % ( + m.id, m.name, + x.filename, m.linenumber, + msgmap[m.id])) + return True + fieldset = set() + for f in m.fields: + if f.name in fieldset: + print("ERROR: Duplicate field %s in message %s (%s:%u)" % ( + f.name, m.name, + x.filename, m.linenumber)) + return True + fieldset.add(f.name) + msgmap[m.id] = '%s (%s:%u)' % (m.name, x.filename, m.linenumber) + return False + + + +def total_msgs(xml): + '''count total number of msgs''' + count = 0 + for x in xml: + count += len(x.message) + return count + +def mkdir_p(dir): + '''like mkdir -p''' + if not dir: + return + if dir.endswith("/"): + mkdir_p(dir[:-1]) + return + if os.path.isdir(dir): + return + mkdir_p(os.path.dirname(dir)) + os.mkdir(dir) + +# check version consistent +# add test.xml +# finish test suite +# printf style error macro, if defined call errors diff --git a/files/mavlink_generator/mavtemplate.py b/files/mavlink_generator/mavtemplate.py new file mode 100644 index 0000000000000000000000000000000000000000..6ef0153150e45d5fd0f6c0da54f0dbb242a93fc1 --- /dev/null +++ b/files/mavlink_generator/mavtemplate.py @@ -0,0 +1,121 @@ +#!/usr/bin/env python +''' +simple templating system for mavlink generator + +Copyright Andrew Tridgell 2011 +Released under GNU GPL version 3 or later +''' + +from mavparse import MAVParseError + +class MAVTemplate(object): + '''simple templating system''' + def __init__(self, + start_var_token="${", + end_var_token="}", + start_rep_token="${{", + end_rep_token="}}", + trim_leading_lf=True, + checkmissing=True): + self.start_var_token = start_var_token + self.end_var_token = end_var_token + self.start_rep_token = start_rep_token + self.end_rep_token = end_rep_token + self.trim_leading_lf = trim_leading_lf + self.checkmissing = checkmissing + + def find_end(self, text, start_token, end_token): + '''find the of a token. + Returns the offset in the string immediately after the matching end_token''' + if not text.startswith(start_token): + raise MAVParseError("invalid token start") + offset = len(start_token) + nesting = 1 + while nesting > 0: + idx1 = text[offset:].find(start_token) + idx2 = text[offset:].find(end_token) + if idx1 == -1 and idx2 == -1: + raise MAVParseError("token nesting error") + if idx1 == -1 or idx1 > idx2: + offset += idx2 + len(end_token) + nesting -= 1 + else: + offset += idx1 + len(start_token) + nesting += 1 + return offset + + def find_var_end(self, text): + '''find the of a variable''' + return self.find_end(text, self.start_var_token, self.end_var_token) + + def find_rep_end(self, text): + '''find the of a repitition''' + return self.find_end(text, self.start_rep_token, self.end_rep_token) + + def substitute(self, text, subvars={}, + trim_leading_lf=None, checkmissing=None): + '''substitute variables in a string''' + + if trim_leading_lf is None: + trim_leading_lf = self.trim_leading_lf + if checkmissing is None: + checkmissing = self.checkmissing + + # handle repititions + while True: + subidx = text.find(self.start_rep_token) + if subidx == -1: + break + endidx = self.find_rep_end(text[subidx:]) + if endidx == -1: + raise MAVParseError("missing end macro in %s" % text[subidx:]) + part1 = text[0:subidx] + part2 = text[subidx+len(self.start_rep_token):subidx+(endidx-len(self.end_rep_token))] + part3 = text[subidx+endidx:] + a = part2.split(':') + field_name = a[0] + rest = ':'.join(a[1:]) + v = getattr(subvars, field_name, None) + if v is None: + raise MAVParseError('unable to find field %s' % field_name) + t1 = part1 + for f in v: + t1 += self.substitute(rest, f, trim_leading_lf=False, checkmissing=False) + if len(v) != 0 and t1[-1] in ["\n", ","]: + t1 = t1[:-1] + t1 += part3 + text = t1 + + if trim_leading_lf: + if text[0] == '\n': + text = text[1:] + while True: + idx = text.find(self.start_var_token) + if idx == -1: + return text + endidx = text[idx:].find(self.end_var_token) + if endidx == -1: + raise MAVParseError('missing end of variable: %s' % text[idx:idx+10]) + varname = text[idx+2:idx+endidx] + if isinstance(subvars, dict): + if not varname in subvars: + if checkmissing: + raise MAVParseError("unknown variable in '%s%s%s'" % ( + self.start_var_token, varname, self.end_var_token)) + return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars, + trim_leading_lf=False, checkmissing=False) + value = subvars[varname] + else: + value = getattr(subvars, varname, None) + if value is None: + if checkmissing: + raise MAVParseError("unknown variable in '%s%s%s'" % ( + self.start_var_token, varname, self.end_var_token)) + return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars, + trim_leading_lf=False, checkmissing=False) + text = text.replace("%s%s%s" % (self.start_var_token, varname, self.end_var_token), str(value)) + return text + + def write(self, file, text, subvars={}, trim_leading_lf=True): + '''write to a file with variable substitution''' + file.write(self.substitute(text, subvars=subvars, trim_leading_lf=trim_leading_lf)) diff --git a/files/parameter_tooltips/MAV_AUTOPILOT_PIXHAWK-MAV_TYPE_QUADROTOR.txt b/files/parameter_tooltips/MAV_AUTOPILOT_PIXHAWK-MAV_TYPE_QUADROTOR.txt deleted file mode 100644 index 610873647651e034a665f5d2d85dd53cf41a8a47..0000000000000000000000000000000000000000 --- a/files/parameter_tooltips/MAV_AUTOPILOT_PIXHAWK-MAV_TYPE_QUADROTOR.txt +++ /dev/null @@ -1,3 +0,0 @@ -EEPROM,variable name,Min,Max,Default,Multiplier,Enabled (0 = no, 1 = yes),Comment -HDNG2RLL_P, 0, 5, 0.7, 1, 1, NAV_ROLL_P - Navigation control gains. Tuning values for the navigation control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction. -SYS_TYPE, 0, 15, 1, 1, 1, System type (airframe) \ No newline at end of file diff --git a/files/parameter_tooltips/MAV_AUTOPILOT_PIXHAWK-MAV_TYPE_FIXED_WING.txt b/files/pixhawk/quadrotor/parameter_tooltips/tooltips.txt similarity index 100% rename from files/parameter_tooltips/MAV_AUTOPILOT_PIXHAWK-MAV_TYPE_FIXED_WING.txt rename to files/pixhawk/quadrotor/parameter_tooltips/tooltips.txt diff --git a/files/quadrotor/pixhawk/parameters/parameters-bravo-icra2012.txt b/files/quadrotor/pixhawk/parameters/parameters-bravo-icra2012.txt deleted file mode 100644 index 4344a5483afcccaba0a80f4d73c490ac48617d4e..0000000000000000000000000000000000000000 --- a/files/quadrotor/pixhawk/parameters/parameters-bravo-icra2012.txt +++ /dev/null @@ -1,119 +0,0 @@ -# Onboard parameters for system BRAVO -# -# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT) -42 1 HANDLEWPDELAY 0.20000000298 -42 1 POSFILTER 1 -42 1 PROTDELAY 40 -42 1 PROTTIMEOUT 2 -42 1 SETPOINTDELAY 1 -42 1 YAWTOLERANCE 0.174500003457 -42 200 ACC_NAV_OFFS_X 0 -42 200 ACC_NAV_OFFS_Y 0 -42 200 ACC_NAV_OFFS_Z -1000 -42 200 ATT_KAL_KACC 0.00329999998212 -42 200 ATT_KAL_YAWMOD 3 -42 200 ATT_OFFSET_X 0 -42 200 ATT_OFFSET_Y 0 -42 200 ATT_OFFSET_Z 0 -42 200 CAL_ACC_X 0 -42 200 CAL_ACC_Y 0 -42 200 CAL_ACC_Z 0 -42 200 CAL_FIT_ACTIVE 0 -42 200 CAL_FIT_GYRO_X 31496.8007812 -42 200 CAL_FIT_GYRO_Y 29383.4003906 -42 200 CAL_FIT_GYRO_Z 30151.0996094 -42 200 CAL_GYRO_X 29760 -42 200 CAL_GYRO_Y 29671 -42 200 CAL_GYRO_Z 29572 -42 200 CAL_MAG_X 375 -42 200 CAL_MAG_Y -25 -42 200 CAL_MAG_Z -1000 -42 200 CAL_PRES_DIFF 10000 -42 200 CAL_TEMP 29557 -42 200 CAM_ANG_X_FAC 0 -42 200 CAM_ANG_X_OFF 0 -42 200 CAM_ANG_Y_FAC 0 -42 200 CAM_ANG_Y_OFF 0.81099998951 -42 200 CAM_EXP 1000 -42 200 CAM_INTERVAL 200000 -42 200 DEBUG_1 0 -42 200 DEBUG_2 0 -42 200 DEBUG_3 0 -42 200 DEBUG_4 0 -42 200 DEBUG_5 1 -42 200 DEBUG_6 0 -42 200 GPS_MODE 0 -42 200 KAL_VEL_AX 1 -42 200 KAL_VEL_AY 1 -42 200 KAL_VEL_BX 0 -42 200 KAL_VEL_BY 0 -42 200 MIX_OFFSET 1 -42 200 MIX_POSITION 1 -42 200 MIX_POS_YAW 1 -42 200 MIX_REMOTE 0 -42 200 MIX_Z_POSITION 1 -42 200 PID_ATT_AWU 0.300000011921 -42 200 PID_ATT_D 30 -42 200 PID_ATT_I 60 -42 200 PID_ATT_LIM 100 -42 200 PID_ATT_P 90 -42 200 PID_POS_AWU 5 -42 200 PID_POS_D 2.20000004768 -42 200 PID_POS_I 0.10000000149 -42 200 PID_POS_LIM 0.20000000298 -42 200 PID_POS_P 2 -42 200 PID_POS_Z_AWU 3 -42 200 PID_POS_Z_D 0.25 -42 200 PID_POS_Z_I 0.300000011921 -42 200 PID_POS_Z_LIM 0.300000011921 -42 200 PID_POS_Z_P 0.25 -42 200 PID_YAWPOS_AWU 1 -42 200 PID_YAWPOS_D 1 -42 200 PID_YAWPOS_I 0.10000000149 -42 200 PID_YAWPOS_LIM 3 -42 200 PID_YAWPOS_P 5 -42 200 PID_YAWSPEED_D 0 -42 200 PID_YAWSPEED_I 5 -42 200 PID_YAWSPEED_P 15 -42 200 PID_YAWSPE_AWU 1 -42 200 PID_YAWSPE_LIM 50 -42 200 POS_ESTIM_MODE 1 -42 200 POS_HOV_TRUST 0.550000011921 -42 200 POS_SON_MODE 0 -42 200 POS_SON_SCALE 1 -42 200 POS_SP_ACCEPT 1 -42 200 POS_SP_X -0.0329026989639 -42 200 POS_SP_Y -0.0478124991059 -42 200 POS_SP_YAW 0 -42 200 POS_SP_Z -0.643148005009 -42 200 POS_TIMEOUT 2000000 -42 200 POS_YAW_TRACK 0 -42 200 RC_NICK_CHAN 1 -42 200 RC_ROLL_CHAN 2 -42 200 RC_SAFETY_CHAN 6 -42 200 RC_THRUST_CHAN 3 -42 200 RC_TRIM_CHAN 0 -42 200 RC_TUNE_CHAN1 5 -42 200 RC_TUNE_CHAN2 6 -42 200 RC_TUNE_CHAN3 7 -42 200 RC_TUNE_CHAN4 5 -42 200 RC_YAW_CHAN 4 -42 200 SEND_DEBUGCHAN 0 -42 200 SLOT_ATTITUDE 1 -42 200 SLOT_CONTROL 0 -42 200 SLOT_RAW_IMU 0 -42 200 SLOT_RC 1 -42 200 SYS_COMP_ID 200 -42 200 SYS_ID 42 -42 200 SYS_IMU_RESET 0 -42 200 SYS_SW_VER 2000 -42 200 SYS_TYPE 2 -42 200 UART_0_BAUD 115200 -42 200 UART_1_BAUD 115200 -42 200 VEL_DAMP 0.949999988079 -42 200 VEL_OFFSET_X 0 -42 200 VEL_OFFSET_Y 0 -42 200 VEL_OFFSET_Z 0 -42 200 VICON_TKO_DIST 0.5 -42 200 VICON_TKO_TIME 2 -42 200 VIS_OUTL_TRESH 0.20000000298 diff --git a/files/quadrotor/pixhawk/parameters/parameters-bravo-vicon.txt b/files/quadrotor/pixhawk/parameters/parameters-bravo-vicon.txt deleted file mode 100644 index 724a84f3378234de03c2ff85e2c79772afecf1b6..0000000000000000000000000000000000000000 --- a/files/quadrotor/pixhawk/parameters/parameters-bravo-vicon.txt +++ /dev/null @@ -1,113 +0,0 @@ -# Onboard parameters for system BRAVO -# -# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT) -42 200 ACC_NAV_OFFS_X 0 -42 200 ACC_NAV_OFFS_Y 0 -42 200 ACC_NAV_OFFS_Z -1000 -42 200 ATT_KAL_KACC 0.00329999998212 -42 200 ATT_KAL_YAWMOD 3 -42 200 ATT_OFFSET_X 0 -42 200 ATT_OFFSET_Y 0 -42 200 ATT_OFFSET_Z 0 -42 200 CAL_ACC_X 0 -42 200 CAL_ACC_Y 0 -42 200 CAL_ACC_Z 0 -42 200 CAL_FIT_ACTIVE 0 -42 200 CAL_FIT_GYRO_X 31496.8007812 -42 200 CAL_FIT_GYRO_Y 29383.4003906 -42 200 CAL_FIT_GYRO_Z 30151.0996094 -42 200 CAL_GYRO_X 29760 -42 200 CAL_GYRO_Y 29671 -42 200 CAL_GYRO_Z 29572 -42 200 CAL_MAG_X 375 -42 200 CAL_MAG_Y -25 -42 200 CAL_MAG_Z -1000 -42 200 CAL_PRES_DIFF 10000 -42 200 CAL_TEMP 29557 -42 200 CAM_ANG_X_FAC 0 -42 200 CAM_ANG_X_OFF 0 -42 200 CAM_ANG_Y_FAC 0 -42 200 CAM_ANG_Y_OFF 0.898000001907 -42 200 CAM_EXP 1000 -42 200 CAM_INTERVAL 200000 -42 200 DEBUG_1 0 -42 200 DEBUG_2 0 -42 200 DEBUG_3 0 -42 200 DEBUG_4 0 -42 200 DEBUG_5 1 -42 200 DEBUG_6 0 -42 200 GPS_MODE 0 -42 200 KAL_VEL_AX 1 -42 200 KAL_VEL_AY 1 -42 200 KAL_VEL_BX 0 -42 200 KAL_VEL_BY 0 -42 200 MIX_OFFSET 1 -42 200 MIX_POSITION 1 -42 200 MIX_POS_YAW 1 -42 200 MIX_REMOTE 0 -42 200 MIX_Z_POSITION 1 -42 200 PID_ATT_AWU 0.300000011921 -42 200 PID_ATT_D 30 -42 200 PID_ATT_I 60 -42 200 PID_ATT_LIM 100 -42 200 PID_ATT_P 90 -42 200 PID_POS_AWU 5 -42 200 PID_POS_D 3.5 -42 200 PID_POS_I 0.300000011921 -42 200 PID_POS_LIM 0.20000000298 -42 200 PID_POS_P 3 -42 200 PID_POS_Z_AWU 3 -42 200 PID_POS_Z_D 0.25 -42 200 PID_POS_Z_I 0.300000011921 -42 200 PID_POS_Z_LIM 0.300000011921 -42 200 PID_POS_Z_P 0.25 -42 200 PID_YAWPOS_AWU 1 -42 200 PID_YAWPOS_D 1 -42 200 PID_YAWPOS_I 0.10000000149 -42 200 PID_YAWPOS_LIM 3 -42 200 PID_YAWPOS_P 5 -42 200 PID_YAWSPEED_D 0 -42 200 PID_YAWSPEED_I 5 -42 200 PID_YAWSPEED_P 15 -42 200 PID_YAWSPE_AWU 1 -42 200 PID_YAWSPE_LIM 50 -42 200 POS_ESTIM_MODE 3 -42 200 POS_HOV_TRUST 0.5 -42 200 POS_SON_MODE 0 -42 200 POS_SON_SCALE 1 -42 200 POS_SP_ACCEPT 1 -42 200 POS_SP_X 0.254168212414 -42 200 POS_SP_Y -0.378409773111 -42 200 POS_SP_YAW 0 -42 200 POS_SP_Z -0.0880969688296 -42 200 POS_TIMEOUT 2000000 -42 200 POS_YAW_TRACK 0 -42 200 RC_NICK_CHAN 1 -42 200 RC_ROLL_CHAN 2 -42 200 RC_SAFETY_CHAN 6 -42 200 RC_THRUST_CHAN 3 -42 200 RC_TRIM_CHAN 0 -42 200 RC_TUNE_CHAN1 5 -42 200 RC_TUNE_CHAN2 6 -42 200 RC_TUNE_CHAN3 7 -42 200 RC_TUNE_CHAN4 5 -42 200 RC_YAW_CHAN 4 -42 200 SEND_DEBUGCHAN 0 -42 200 SLOT_ATTITUDE 1 -42 200 SLOT_CONTROL 0 -42 200 SLOT_RAW_IMU 0 -42 200 SLOT_RC 1 -42 200 SYS_COMP_ID 200 -42 200 SYS_ID 42 -42 200 SYS_IMU_RESET 0 -42 200 SYS_SW_VER 2000 -42 200 SYS_TYPE 2 -42 200 UART_0_BAUD 115200 -42 200 UART_1_BAUD 115200 -42 200 VEL_DAMP 0.949999988079 -42 200 VEL_OFFSET_X 0 -42 200 VEL_OFFSET_Y 0 -42 200 VEL_OFFSET_Z 0 -42 200 VICON_TKO_DIST 0.5 -42 200 VICON_TKO_TIME 2 -42 200 VIS_OUTL_TRESH 0.20000000298 diff --git a/files/quadrotor/pixhawk/parameters/parameters-bravo.txt b/files/quadrotor/pixhawk/parameters/parameters-bravo.txt deleted file mode 100644 index 16ed4cb98604ed0fee4d795b3fac9389acae2bad..0000000000000000000000000000000000000000 --- a/files/quadrotor/pixhawk/parameters/parameters-bravo.txt +++ /dev/null @@ -1,119 +0,0 @@ -# Onboard parameters for system MAV 042 -# -# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT) -42 1 HANDLEWPDELAY 0.20000000298 -42 1 POSFILTER 1 -42 1 PROTDELAY 40 -42 1 PROTTIMEOUT 2 -42 1 SETPOINTDELAY 1 -42 1 YAWTOLERANCE 0.174500003457 -42 200 ACC_NAV_OFFS_X 0 -42 200 ACC_NAV_OFFS_Y 0 -42 200 ACC_NAV_OFFS_Z -1000 -42 200 ATT_KAL_KACC 0.00329999998212 -42 200 ATT_KAL_YAWMOD 3 -42 200 ATT_OFFSET_X 0 -42 200 ATT_OFFSET_Y 0 -42 200 ATT_OFFSET_Z -0.0799999982119 -42 200 CAL_ACC_X 0 -42 200 CAL_ACC_Y 0 -42 200 CAL_ACC_Z 0 -42 200 CAL_FIT_ACTIVE 0 -42 200 CAL_FIT_GYRO_X 31496.8007812 -42 200 CAL_FIT_GYRO_Y 29383.4003906 -42 200 CAL_FIT_GYRO_Z 30151.0996094 -42 200 CAL_GYRO_X 29767 -42 200 CAL_GYRO_Y 29654 -42 200 CAL_GYRO_Z 29570 -42 200 CAL_MAG_X 375 -42 200 CAL_MAG_Y -25 -42 200 CAL_MAG_Z -1000 -42 200 CAL_PRES_DIFF 10000 -42 200 CAL_TEMP 29051 -42 200 CAM_ANG_X_FAC 0 -42 200 CAM_ANG_X_OFF 0 -42 200 CAM_ANG_Y_FAC 0 -42 200 CAM_ANG_Y_OFF 0.428000003099 -42 200 CAM_EXP 1000 -42 200 CAM_INTERVAL 200000 -42 200 DEBUG_1 0 -42 200 DEBUG_2 0 -42 200 DEBUG_3 0 -42 200 DEBUG_4 0 -42 200 DEBUG_5 1 -42 200 DEBUG_6 0 -42 200 GPS_MODE 0 -42 200 KAL_VEL_AX 1 -42 200 KAL_VEL_AY 1 -42 200 KAL_VEL_BX 0 -42 200 KAL_VEL_BY 0 -42 200 MIX_OFFSET 0 -42 200 MIX_POSITION 0 -42 200 MIX_POS_YAW 0 -42 200 MIX_REMOTE 0 -42 200 MIX_Z_POSITION 0 -42 200 PID_ATT_AWU 0.300000011921 -42 200 PID_ATT_D 30 -42 200 PID_ATT_I 60 -42 200 PID_ATT_LIM 100 -42 200 PID_ATT_P 90 -42 200 PID_POS_AWU 5 -42 200 PID_POS_D 2 -42 200 PID_POS_I 0.20000000298 -42 200 PID_POS_LIM 0.20000000298 -42 200 PID_POS_P 1.79999995232 -42 200 PID_POS_Z_AWU 3 -42 200 PID_POS_Z_D 0.20000000298 -42 200 PID_POS_Z_I 0.300000011921 -42 200 PID_POS_Z_LIM 0.300000011921 -42 200 PID_POS_Z_P 0.25 -42 200 PID_YAWPOS_AWU 1 -42 200 PID_YAWPOS_D 1 -42 200 PID_YAWPOS_I 0.10000000149 -42 200 PID_YAWPOS_LIM 3 -42 200 PID_YAWPOS_P 5 -42 200 PID_YAWSPEED_D 0 -42 200 PID_YAWSPEED_I 5 -42 200 PID_YAWSPEED_P 15 -42 200 PID_YAWSPE_AWU 1 -42 200 PID_YAWSPE_LIM 50 -42 200 POS_HOV_TRUST 0.300000011921 -42 200 POS_SON_MODE 0 -42 200 POS_SON_SCALE 1 -42 200 POS_SP_ACCEPT 1 -42 200 POS_SP_X 0 -42 200 POS_SP_Y 0 -42 200 POS_SP_YAW 0 -42 200 POS_SP_Z -0.213201999664 -42 200 POS_TIMEOUT 2000000 -42 200 POS_YAW_TRACK 0 -42 200 RC_NICK_CHAN 1 -42 200 RC_ROLL_CHAN 2 -42 200 RC_SAFETY_CHAN 5 -42 200 RC_THRUST_CHAN 3 -42 200 RC_TRIM_CHAN 0 -42 200 RC_TUNE_CHAN1 5 -42 200 RC_TUNE_CHAN2 6 -42 200 RC_TUNE_CHAN3 7 -42 200 RC_TUNE_CHAN4 8 -42 200 RC_YAW_CHAN 4 -42 200 SEND_DEBUGCHAN 0 -42 200 SLOT_ATTITUDE 1 -42 200 SLOT_CONTROL 0 -42 200 SLOT_RAW_IMU 0 -42 200 SLOT_RC 0 -42 200 SYS_COMP_ID 200 -42 200 SYS_ID 42 -42 200 SYS_IMU_RESET 0 -42 200 SYS_SW_VER 2000 -42 200 SYS_TYPE 2 -42 200 UART_0_BAUD 115200 -42 200 UART_1_BAUD 115200 -42 200 VEL_DAMP 0.949999988079 -42 200 VEL_OFFSET_X 0 -42 200 VEL_OFFSET_Y 0 -42 200 VEL_OFFSET_Z 0 -42 200 VICON_MODE 0 -42 200 VICON_TKO_DIST 0.5 -42 200 VICON_TKO_TIME 2 -42 200 VIS_OUTL_TRESH 0.20000000298 diff --git a/files/quadrotor/pixhawk/widgets/pixhawk-widget.qgw b/files/quadrotor/pixhawk/widgets/pixhawk-widget.qgw deleted file mode 100644 index 6add259e9681ad6393eab8198607e1de20173825..0000000000000000000000000000000000000000 --- a/files/quadrotor/pixhawk/widgets/pixhawk-widget.qgw +++ /dev/null @@ -1,14 +0,0 @@ -[PIXHAWK%20Quadrotor%20Commands] -QGC_TOOL_WIDGET_ITEMS\1\TYPE=BUTTON -QGC_TOOL_WIDGET_ITEMS\1\QGC_ACTION_BUTTON_DESCRIPTION=CALIBRATE GYRO -QGC_TOOL_WIDGET_ITEMS\1\QGC_ACTION_BUTTON_BUTTONTEXT=Calibrate -QGC_TOOL_WIDGET_ITEMS\1\QGC_ACTION_BUTTON_ACTIONID=17 -QGC_TOOL_WIDGET_ITEMS\2\TYPE=BUTTON -QGC_TOOL_WIDGET_ITEMS\2\QGC_ACTION_BUTTON_DESCRIPTION=Record logfile and images -QGC_TOOL_WIDGET_ITEMS\2\QGC_ACTION_BUTTON_BUTTONTEXT=Start -QGC_TOOL_WIDGET_ITEMS\2\QGC_ACTION_BUTTON_ACTIONID=21 -QGC_TOOL_WIDGET_ITEMS\3\TYPE=BUTTON -QGC_TOOL_WIDGET_ITEMS\3\QGC_ACTION_BUTTON_DESCRIPTION=Stop recording -QGC_TOOL_WIDGET_ITEMS\3\QGC_ACTION_BUTTON_BUTTONTEXT=Stop -QGC_TOOL_WIDGET_ITEMS\3\QGC_ACTION_BUTTON_ACTIONID=23 -QGC_TOOL_WIDGET_ITEMS\size=3 diff --git a/images/style-outdoor-dark.css b/images/style-outdoor-dark.css new file mode 100644 index 0000000000000000000000000000000000000000..0ad06a80d1deb8f939e9ad7cf6d71f549b28a6fb --- /dev/null +++ b/images/style-outdoor-dark.css @@ -0,0 +1,426 @@ +* { font-family: "Bitstream Vera Sans"; font: "Roman"; font-size: 12px; } +QWidget#colorIcon {} + +QWidget { +background-color: #050508; +color: #FFFFFF; +background-clip: border; +font-size: 11px; +} + +QGroupBox { +border: 1px solid #66666B; +border-radius: 3px; +padding: 10px 0px 0px 0px; +margin-top: 1ex; /* leave space at the top for the title */ +} + +QCheckBox { +/*background-color: #252528;*/ +color: #DDDDDF; +} + +QCheckBox::indicator { + border: 1px solid #777777; + border-radius: 2px; + color: #DDDDDF; + width: 10px; + height: 10px; +} + +QLineEdit { +border: 1px solid #777777; + border-radius: 2px; +} + +QTextEdit { +border: 1px solid #777777; + border-radius: 2px; +} + +QPlainTextEdit { +border: 1px solid #777777; + border-radius: 2px; +} + +QComboBox { +border: 1px solid #777777; + border-radius: 2px; + } + + QCheckBox::indicator:checked { + background-color: #379AC3; + } + + QCheckBox::indicator:checked:hover { + background-color: #379AC3; + } + + QCheckBox::indicator:checked:pressed { + background-color: #379AC3; + } + + QCheckBox::indicator:indeterminate:hover { + image: url(:/images/checkbox_indeterminate_hover.png); + } + + QCheckBox::indicator:indeterminate:pressed { + image: url(:/images/checkbox_indeterminate_pressed.png); + } + + QGroupBox::title { + subcontrol-origin: margin; + subcontrol-position: top center; /* position at the top center */ + margin: 0 3px 0px 3px; + padding: 0 3px 0px 0px; + font: bold 8px; + color: #DDDDDF; + } + + QMainWindow::separator { + background: #090909; + width: 2px; /* when vertical */ + height: 2px; /* when horizontal */ + } + + QMainWindow::separator:hover { + background: white; + } + + QGCToolWidgetItem { + border: 1px solid #66666B; + border-radius: 3px; + padding: 10px 0px 0px 0px; + margin-top: 1ex; /* leave space at the top for the title */ + } + + QDockWidget { + border: 1px solid #32345E; + /* titlebar-close-icon: url(close.png); + titlebar-normal-icon: url(undock.png);*/ + } + + QDockWidget::title { + text-align: left; /* align the text to the left */ + background: lightgray; + padding-left: 5px; + } + + QDockWidget::close-button, QDockWidget::float-button { + border: 1px solid transparent; + background: darkgray; + padding: 0px; + } + + QDockWidget::close-button:hover, QDockWidget::float-button:hover { + background: gray; + } + + QDockWidget::close-button:pressed, QDockWidget::float-button:pressed { + padding: 1px -1px -1px 1px; + } + + + +QDockWidget::close-button, QDockWidget::float-button { + background-color: #181820; + color: #EEEEEE; +} + +QDockWidget::title { + text-align: left; + background: #121214; + color: #4A4A4F; + padding-left: 5px; + height: 10px; + border-bottom: 1px solid #555555; +} + +QSeparator { + color: #EEEEEE; + } + + +QSpinBox { + min-height: 14px; + max-height: 18px; + border: 1px solid #4A4A4F; + border-radius: 5px; +} + +QSpinBox::up-button { + subcontrol-origin: border; + subcontrol-position: top right; /* position at the top right corner */ + border-image: url(:/images/actions/go-up.svg) 1; + border-width: 1px; +} +QSpinBox::down-button { + subcontrol-origin: border; + subcontrol-position: bottom right; /* position at the top right corner */ + border-image: url(:/images/actions/go-down.svg) 1; + border-width: 1px; +} + +QDoubleSpinBox { + min-height: 14px; + max-height: 18px; + border: 1px solid #4A4A4F; + border-radius: 5px; +} + +QDoubleSpinBox::up-button { + subcontrol-origin: border; + subcontrol-position: top right; /* position at the top right corner */ + border-image: url(:/images/actions/go-up.svg) 1; + border-width: 1px; + max-width: 5px; +} +QDoubleSpinBox::down-button { + subcontrol-origin: border; + subcontrol-position: bottom right; /* position at the top right corner */ + border-image: url(:/images/actions/go-down.svg) 1; + border-width: 1px; + max-width: 5px; +} + +QPushButton { + font-weight: bold; + min-height: 18px; + max-height: 18px; + border: 2px solid #4A4A4F; + border-radius: 5px; + padding-left: 5px; + padding-right: 5px; + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208); +} + +QPushButton:checked { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #404040, stop: 1 #808080); + border: 2px solid #379AC3; +} + +QPushButton:pressed { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0); + border: 2px solid #379AC3; +} + +QToolButton { + font-weight: bold; + min-height: 16px; + min-width: 24px; + max-height: 18px; + border: 2px solid #4A4A4F; + border-radius: 5px; + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208); +} + +QToolButton:checked { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535); + border: 2px solid #379AC3; +} + +QToolButton:pressed { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0); + border: 2px solid #379AC3; +} + +QToolTip { + background-color: #090909; + border: 1px solid #379AC3; + border-radius: 3px; + color: #DDDDDF; +} + +QMenu { + border: 1px solid #379AC3; +} + +QMenu::separator { + height: 1px; + background: #379AC3; + margin-top: 8px; + margin-bottom: 4px; + margin-left: 5px; + margin-right: 5px; + } + +QSlider::groove:horizontal { + border: 1px solid #999999; + height: 4px; /* the groove expands to the size of the slider by default. by giving it a height, it has a fixed size */ + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, stop:0 #4A4A4F, stop:1 #4A4A4F); + margin: 2px 0; + } + + QSlider::handle:horizontal { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208); + border: 2px solid #379AC3; + width: 18px; + margin: -5px 0; /* handle is placed by default on the contents rect of the groove. Expand outside the groove */ + border-radius: 3px; + } + + QSlider::groove:vertical { + border: 1px solid #999999; + width: 4px; /* the groove expands to the size of the slider by default. by giving it a height, it has a fixed size */ + background: qlineargradient(x1:0, y1:0, x2:1, y2:0, stop:0 #4A4A4F, stop:1 #4A4A4F); + margin: 2px 0; + } + + QSlider::handle:vertical { + background-color: qlineargradient(x1: 0, y1: 0, x2: 1, y2: 0, stop: 0 #232228, stop: 1 #020208); + border: 2px solid #379AC3; + height: 18px; + margin: 0 -5px; /* handle is placed by default on the contents rect of the groove. Expand outside the groove */ + border-radius: 3px; + } + +QPushButton#forceLandButton { + font-weight: bold; + min-height: 30px; + color: #000000; + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, + stop:0 #ffee01, stop:1 #ae8f00) url("ICONDIR/control/emergency-button.png"); + background-clip: border; + border-width: 1px; + border-color: #555555; + border-radius: 5px; +} + +QPushButton:pressed#forceLandButton { + font-weight: bold; + min-height: 30px; + color: #000000; + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, + stop:0 #bbaa00, stop:1 #a05b00) url("ICONDIR/control/emergency-button.png"); + background-clip: border; + border-width: 1px; + border-color: #555555; + border-radius: 5px; +} + +QPushButton#killButton { + font-weight: bold; + min-height: 30px; + color: #000000; + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, + stop:0 #ffb917, stop:1 #b37300) url("ICONDIR/control/emergency-button.png"); + background-clip: border; + border-width: 1px; + border-color: #555555; + border-radius: 5px; +} + +QPushButton:pressed#killButton { + font-weight: bold; + min-height: 30px; + color: #000000; + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, + stop:0 #bb8500, stop:1 #903000) url("ICONDIR/control/emergency-button.png"); + background-clip: border; + border-width: 1px; + border-color: #555555; + border-radius: 5px; +} + +QPushButton#controlButton { + min-height: 25px; + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #A0AE00, stop: 1 #909E00); +} + +QPushButton:checked#controlButton { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #b76f11, stop: 1 #e1a718); +} + +QProgressBar { + border: 1px solid #4A4A4F; + border-radius: 4px; + text-align: center; + padding: 2px; + color: #DDDDDF; + background-color: #111118; + height: 10px; +} + +QProgressBar:horizontal { + height: 9px; +} + +QProgressBar:vertical { + width: 9px; +} + +QProgressBar::chunk { + background-color: #3C7B9E; +} + +QProgressBar::chunk#batteryBar { + background-color: green; +} + +QProgressBar::chunk#speedBar { + background-color: yellow; +} + +QProgressBar::chunk#thrustBar { + background-color: orange; +} + +QDialog { + border: 1px solid #62676B; + border-radius: 2px; +} + + QTabWidget::pane { /* The tab widget frame */ + border: 1px solid #62676B; + border-radius: 2px; + position: absolute; + top: -0.5em; + } + + QTabWidget::tab-bar { + alignment: center; + } + + /* Style the tab using the tab sub-control. Note that + it reads QTabBar _not_ QTabWidget */ + QTabBar::tab { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535); + border: 2px solid #62676B; + border-radius: 4px; + min-width: 8ex; + padding: 2px; + } + + QTabBar::tab:selected, QTabBar::tab:hover { + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535); + border: 2px solid #379AC3; + } + + QTabBar::tab:selected { + border: 2px solid #379AC3; + } + +QLabel { + background-color: transparent; +} + +QLabel#toolBarNameLabel { + font: bold 16px; + color: #3C7B9E; +} + +QLabel#toolBarModeLabel { + font: 12px; +} + +QLabel#toolBarStateLabel { + font: 12px; + color: #3C7B9E; +} + +QLabel#toolBarMessageLabel { + font: 12px; + font-style: italic; + color: #3C7B9E; +} + diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index a587fb108d1018e69fc1cbec53ec3bf476aac444..8fc31aafd9534687bd43d47df5e2339ddd61d99f 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -236,6 +236,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit systemTypeSet(this, type); } + // FIXME update + //emit armingChanged(uasId, ); + QString audiostring = "System " + getUASName(); QString stateAudio = ""; QString modeAudio = ""; @@ -297,11 +300,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) GAudioOutput::instance()->say(audiostring.toLower()); } - if (state.system_status == MAV_STATE_POWEROFF) - { - emit systemRemoved(this); - emit systemRemoved(); - } +// if (state.system_status == MAV_STATE_POWEROFF) +// { +// emit systemRemoved(this); +// emit systemRemoved(); +// } } break; diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 8dce73f70c078052b3abd3ac256d67cb8b23d25f..5634775f99bbefbcd5107ec8b38f879df7a4552e 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -358,6 +358,8 @@ signals: void dropRateChanged(int systemId, float receiveDrop); /** @brief Robot mode has changed */ void modeChanged(int sysId, QString status, QString description); + /** @brief Robot armed state has changed */ + void armingChanged(int sysId, QString armingState); /** @brief A command has been issued **/ void commandSent(int command); /** @brief The connection status has changed **/ diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 53e0d31c10fdd15985c80a71645428acfdda68ee..5896f3577aa7b5d0f04d4795f9754189d2aa1a13 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -633,7 +633,7 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) void MainWindow::loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType) { - QString defaultsDir = qApp->applicationDirPath() + "/files/" + systemType.toLower() + "/" + autopilotType.toLower() + "/widgets/"; + QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; QDir widgets(defaultsDir); QStringList files = widgets.entryList(); diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index e167629fc979e367fddda23418d1881138065545..4b02cdb9995212980bf2eba6490eb5c641e5f4f6 100644 --- a/src/ui/QGCParamWidget.cc +++ b/src/ui/QGCParamWidget.cc @@ -150,8 +150,8 @@ void QGCParamWidget::loadSettings() void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QString& airframe) { QDir appDir = QDir::current(); - appDir.cd("files/parameter_tooltips"); - QString fileName = QString("MAV_AUTOPILOT_%1-MAV_TYPE_%2.txt").arg(autopilot).arg(airframe); + appDir.cd("files"); + QString fileName = QString("/%1/%2/parameter_tooltips/tooltips.txt").arg(autopilot.toLower()).arg(airframe.toLower()); QString filePath = appDir.filePath(fileName); QFile paramMetaFile(filePath); diff --git a/src/ui/QGCToolBar.cc b/src/ui/QGCToolBar.cc index 2562d82017f402bd842bbc73c01773f13b509e6b..b3332739a386d61f0ac239106cb993e487e86d65 100644 --- a/src/ui/QGCToolBar.cc +++ b/src/ui/QGCToolBar.cc @@ -50,6 +50,8 @@ QGCToolBar::QGCToolBar(QWidget *parent) : // Add MAV widget symbolButton = new QToolButton(this); toolBarNameLabel = new QLabel("------", this); + toolBarSafetyLabel = new QLabel("SAFE", this); + toolBarSafetyLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 14px; color: #14C814; }"); toolBarModeLabel = new QLabel("------", this); toolBarModeLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 14px; color: #3C7B9E; }"); toolBarStateLabel = new QLabel("------", this); @@ -70,6 +72,7 @@ QGCToolBar::QGCToolBar(QWidget *parent) : symbolButton->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 0px 0px 20px; background-color: none; }"); addWidget(symbolButton); addWidget(toolBarNameLabel); + addWidget(toolBarSafetyLabel); addWidget(toolBarModeLabel); addWidget(toolBarStateLabel); addWidget(toolBarBatteryBar); @@ -151,6 +154,39 @@ void QGCToolBar::logging(bool enabled) void QGCToolBar::addPerspectiveChangeAction(QAction* action) { insertAction(toggleLoggingAction, action); + + // Set tab style + QWidget* widget = widgetForAction(action); + widget->setStyleSheet("\ + * { font-weight: bold; min-height: 16px; min-width: 24px; \ + border-top: 1px solid #BBBBBB; \ + border-bottom: 0px; \ + border-left: 1px solid #BBBBBB; \ + border-right: 1px solid #BBBBBB; \ + border-top-left-radius: 5px; \ + border-top-right-radius: 5px; \ + border-bottom-left-radius: 0px; \ + border-bottom-right-radius: 0px; \ + max-height: 22px; \ + margin-top: 4px; \ + margin-left: 2px; \ + margin-bottom: 0px; \ + margin-right: 2px; \ + background-color: #222222; \ + } \ + *:checked { \ + background-color: #000000; \ + border-top: 2px solid #379AC3; \ + border-bottom: 0px; \ + border-left: 2px solid #379AC3; \ + border-right: 2px solid #379AC3; \ + } \ + *:pressed { \ + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0); \ + border-top: 2px solid #379AC3; \ + border-bottom: 0px; \ + border-left: 2px solid #379AC3; \ + border-right: 2px solid #379AC3; }"); } void QGCToolBar::setActiveUAS(UASInterface* active) diff --git a/src/ui/QGCToolBar.h b/src/ui/QGCToolBar.h index 23c0703f1226d76ee39ff77a3e31e4a6904feb88..d6842565daa407a7b37600fc7835e7ef7ddac6d8 100644 --- a/src/ui/QGCToolBar.h +++ b/src/ui/QGCToolBar.h @@ -75,6 +75,7 @@ protected: UASInterface* mav; QToolButton* symbolButton; QLabel* toolBarNameLabel; + QLabel* toolBarSafetyLabel; QLabel* toolBarModeLabel; QLabel* toolBarStateLabel; QLabel* toolBarWpLabel;