devbharat 10 years ago
parent
commit
927056340d
  1. BIN
      Documentation/px4_hil/SITL_Diagram.png
  2. BIN
      Documentation/px4_hil/SITL_Diagram_QGC.png
  3. 98
      Documentation/px4_hil/UserGuide.md
  4. 0
      Documentation/px4_hil/docs/readme.txt
  5. 2403
      Documentation/px4_hil/px4_hil.doxyfile
  6. 11
      ROMFS/px4fmu_common/init.d/rc.sensors
  7. 2
      ROMFS/px4fmu_common/init.d/rc.usb
  8. 11
      ROMFS/px4fmu_common/init.d/rcS
  9. 98
      Tools/px4params/srcparser.py
  10. 8
      Tools/px4params/srcscanner.py
  11. 5
      Tools/px_process_params.py
  12. 2
      package.xml
  13. 12
      src/drivers/boards/aerocore/board_config.h
  14. 12
      src/drivers/boards/px4fmu-v1/board_config.h
  15. 13
      src/drivers/boards/px4fmu-v2/board_config.h
  16. 48
      src/drivers/gps/gps.cpp
  17. 15
      src/drivers/stm32/adc/adc.cpp
  18. 1
      src/modules/camera_trigger/camera_trigger_params.c
  19. 2
      src/modules/commander/commander_params.c
  20. 2
      src/modules/commander/mag_calibration.cpp
  21. 8
      src/modules/mavlink/mavlink_main.cpp
  22. 21
      src/modules/mavlink/mavlink_messages.cpp
  23. 63
      src/modules/navigator/mission.cpp
  24. 8
      src/modules/navigator/mission.h
  25. 22
      src/modules/sensors/sensors.cpp
  26. 6
      src/platforms/qurt/px4_layer/main.cpp
  27. 3
      src/platforms/ros/nodes/position_estimator/position_estimator.cpp
  28. 2
      src/platforms/ros/nodes/position_estimator/position_estimator.h

BIN
Documentation/px4_hil/SITL_Diagram.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 79 KiB

BIN
Documentation/px4_hil/SITL_Diagram_QGC.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 74 KiB

98
Documentation/px4_hil/UserGuide.md

@ -0,0 +1,98 @@ @@ -0,0 +1,98 @@
[TOC]
# Introduction
The HIL architecture allows you to test the flight stack replacing the real physical vehicle and sensors with a simulator of vehicle dynamics and sensor outputs. The flight stack "is not aware" that it is not on a real vehicle. This is a powerful tool for develping and testing code rapidly in a benchtop environment.
The flight stack can be run anywhere that supports a network connection to the simulator (with sufficient bandwidth and latency to transport the sensor and actuator messages). This can be on a standard linux workstation, an on-target linux image, or the on-target DSP image. These modes can be selected based on the goals of the testing. Workstation is useful for rapid testing in a tool-rich environment. DSP image testing is the closest to the final implementation, so is useful for testing actual HW operation, other than the physical sensing and actuation.
## Px4 High-level HIL Architecture
A diagram of the setup described is shown here. Note that UDP port numbers are only displayed on the socket server and are left blank on the socket client.
(???NOTES: This diagram needs to be updated to use control inputs over UDP, either from QGC or from other)
![SITL Diagram](./SITL_Diagram_QGC.png "SITL Diagram")
## Requirements
The simulator that is currently supported is jMAVSim. The setup described here requires PX4 and jMAVSim installed and running. qGroundControl (QGC) is also required because it is the supported method of providing manual control commands.
## Assumptions
# Compiling Code
## JMAVSim
### Platform Requirements
Linux with java-1.7.x or greater
### Build Instructions
In a clean directory
```
> git clone https://github.com/PX4/jMAVSim.git
> cd jMAVSim
> git submodule init
> git submodule update
> ant
```
## qGroundControl
### Platform Requirements
Windows 7
Logitech Gamepad F310 joystick controller
### Download/Install Instructions
Download QGC from http://qgroundcontrol.org/downloads and install using the windows executable.
## PX4
### Platfrom Requirements
Linux or Eagle with a working IP interface (?? does this need further instructions?)
### Build Host Requirements
(???Notes: Windows?)
### Download & Build Instructions
### Installing binaries on the Qualcomm Target
# Running PX4 in HIL Mode
## Starting PX4 on Qualcomm Eagle
```
> adb shell
# bash
root@linaro-developer:/# cd ???
root@linaro-developer:/# ./mainapp
App name: mainapp
Enter a command and its args:
uorb start
muorb start
mavlink start -u 14556
simulator start -p
```
## Starting jMAVSim
In the directory where jMAVSim is installed
```
java -cp lib/*:out/production/jmavsim.jar me.drton.jmavsim.Simulator -udp <IPADDR>:14560 -n 100
```
replacing <IPADDR> with the IP address of the machine running PX4 (Eagle). This can be found by running "ifconfig" on that machine.
## Starting qGroundControl
Launch the qGroundControl application
1. Set up the communication to the flight stack. In the menu File:Settings:CommLinks, select Add. Enter a Link Name of your choice. Select Link Type: UDP. Set the listening port to an unused port (example: 14561). Select Add. Enter the IP address and port of the PX4 Mavlink app, which is <IPADDR>:14556 with <IPADDR> being the IP address of the Eagle board. Select OK.
1. Set up the joystick. Plug in the joystick to your Windows machine. In the menu File:Settings:CommLinks, check Enable Controllers. Select "Gamepad F310". Select "Manual". Set the axes/channel mapping to 0:Yaw, 1:Throttle, 2:unset, 3:Pitch, 4:Roll. Seletct "Inverted" for the throttle axis. Click "Calibrate range". Move the right joystick through its full range of motion. Move the left joystick full left then full right. Move the left joystick full forward (but not full backward). Click "end calibration."
1. Connect to the flight stack. Click Analyze. Click the "Connect" button in the upper right, and select the connection that you created in the first step.
You should now be connected to the flight stack. You can see incoming Mavlink packets using the MAVLink Instpector (from Advanced:Tool Widgets)
## Controlling PX4 flight in HIL Mode
The joystick can now be used to fly the simulated vehicle. The jMAVSim world visualization gives a FPV view, and QGC can be used to display instruments such as artificial horizon and maps (if GPS simulation is enabled).
# Debugging/FAQ

0
Documentation/px4_hil/docs/readme.txt

2403
Documentation/px4_hil/px4_hil.doxyfile

File diff suppressed because it is too large Load Diff

11
ROMFS/px4fmu_common/init.d/rc.sensors

@ -115,17 +115,6 @@ if px4flow start & @@ -115,17 +115,6 @@ if px4flow start &
then
fi
if param compare SENS_EN_LL40LS 1
then
if pwm_input start
then
fi
if ll40ls start pwm
then
fi
fi
#
# Start sensors
#

2
ROMFS/px4fmu_common/init.d/rc.usb

@ -13,7 +13,7 @@ mavlink stream -d /dev/ttyACM0 -s DISTANCE_SENSOR -r 10 @@ -13,7 +13,7 @@ mavlink stream -d /dev/ttyACM0 -s DISTANCE_SENSOR -r 10
mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 100
mavlink stream -d /dev/ttyACM0 -s ACTUATOR_CONTROL_TARGET0 -r 30
mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5
mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS -r 5
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
mavlink stream -d /dev/ttyACM0 -s POSITION_TARGET_GLOBAL_INT -r 10
mavlink stream -d /dev/ttyACM0 -s LOCAL_POSITION_NED -r 30

11
ROMFS/px4fmu_common/init.d/rcS

@ -451,6 +451,17 @@ then @@ -451,6 +451,17 @@ then
fi
fi
# Start sensors depending on the interface being up
if param compare SENS_EN_LL40LS 1
then
if pwm_input start
then
if ll40ls start pwm
then
fi
fi
fi
if [ $MAVLINK_F == default ]
then
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s

98
Tools/px4params/srcparser.py

@ -101,6 +101,7 @@ class SourceParser(object): @@ -101,6 +101,7 @@ class SourceParser(object):
re_cut_type_specifier = re.compile(r'[a-z]+$')
re_is_a_number = re.compile(r'^-?[0-9\.]')
re_remove_dots = re.compile(r'\.+$')
re_remove_carriage_return = re.compile('\n+')
valid_tags = set(["group", "board", "min", "max", "unit"])
@ -188,12 +189,20 @@ class SourceParser(object): @@ -188,12 +189,20 @@ class SourceParser(object):
if last_comment_line:
state = "comment-processed"
else:
tp = None
name = None
defval = ""
# Non-empty line outside the comment
m = self.re_parameter_definition.match(line)
if m:
tp, name, defval = m.group(1, 2, 3)
else:
m = self.re_px4_parameter_definition.match(line)
if m:
tp, name = m.group(1, 2)
if tp is not None:
# Remove trailing type specifier from numbers: 0.1f => 0.1
if self.re_is_a_number.match(defval):
if defval != "" and self.re_is_a_number.match(defval):
defval = self.re_cut_type_specifier.sub('', defval)
param = Parameter(name, tp, defval)
param.SetField("short_desc", name)
@ -202,52 +211,71 @@ class SourceParser(object): @@ -202,52 +211,71 @@ class SourceParser(object):
group = "Miscellaneous"
if state == "comment-processed":
if short_desc is not None:
param.SetField("short_desc",
self.re_remove_dots.sub('', short_desc))
param.SetField("short_desc", self.re_remove_dots.sub('', short_desc))
if long_desc is not None:
long_desc = self.re_remove_carriage_return.sub(' ', long_desc)
param.SetField("long_desc", long_desc)
for tag in tags:
if tag == "group":
group = tags[tag]
elif tag not in self.valid_tags:
sys.stderr.write("Skipping invalid "
"documentation tag: '%s'\n" % tag)
sys.stderr.write("Skipping invalid documentation tag: '%s'\n" % tag)
return False
else:
param.SetField(tag, tags[tag])
# Store the parameter
if group not in self.param_groups:
self.param_groups[group] = ParameterGroup(group)
self.param_groups[group].AddParameter(param)
else:
# Nasty code dup, but this will all go away soon, so quick and dirty (DonLakeFlyer)
m = self.re_px4_parameter_definition.match(line)
if m:
tp, name = m.group(1, 2)
param = Parameter(name, tp)
param.SetField("short_desc", name)
# If comment was found before the parameter declaration,
# inject its data into the newly created parameter.
group = "Miscellaneous"
if state == "comment-processed":
if short_desc is not None:
param.SetField("short_desc",
self.re_remove_dots.sub('', short_desc))
if long_desc is not None:
param.SetField("long_desc", long_desc)
for tag in tags:
if tag == "group":
group = tags[tag]
elif tag not in self.valid_tags:
sys.stderr.write("Skipping invalid "
"documentation tag: '%s'\n" % tag)
else:
param.SetField(tag, tags[tag])
# Store the parameter
if group not in self.param_groups:
self.param_groups[group] = ParameterGroup(group)
self.param_groups[group].AddParameter(param)
# Reset parsed comment.
state = None
state = None
return True
def IsNumber(self, numberString):
try:
float(numberString)
return True
except ValueError:
return False
def Validate(self):
"""
Validates the parameter meta data.
"""
seenParamNames = []
for group in self.GetParamGroups():
for param in group.GetParams():
name = param.GetName()
board = param.GetFieldValue("board")
# Check for duplicates
name_plus_board = name + "+" + board
for seenParamName in seenParamNames:
if seenParamName == name_plus_board:
sys.stderr.write("Duplicate parameter definition: {0}\n".format(name_plus_board))
return False
seenParamNames.append(name_plus_board)
# Validate values
default = param.GetDefault()
min = param.GetFieldValue("min")
max = param.GetFieldValue("max")
#sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max))
if default != "" and not self.IsNumber(default):
sys.stderr.write("Default value not number: {0} {1}\n".format(name, default))
return False
if min != "":
if not self.IsNumber(min):
sys.stderr.write("Min value not number: {0} {1}\n".format(name, min))
return False
if default != "" and float(default) < float(min):
sys.stderr.write("Default value is smaller than min: {0} default:{1} min:{2}\n".format(name, default, min))
return False
if max != "":
if not self.IsNumber(max):
sys.stderr.write("Max value not number: {0} {1}\n".format(name, max))
return False
if default != "" and float(default) > float(max):
sys.stderr.write("Default value is larger than max: {0} default:{1} max:{2}\n".format(name, default, max))
return False
return True
def GetParamGroups(self):
"""

8
Tools/px4params/srcscanner.py

@ -17,8 +17,10 @@ class SourceScanner(object): @@ -17,8 +17,10 @@ class SourceScanner(object):
for dirname, dirnames, filenames in os.walk(srcdir):
for filename in filenames:
if filename.endswith(extensions):
path = os.path.join(dirname, filename)
self.ScanFile(path, parser)
path = os.path.join(dirname, filename)
if not self.ScanFile(path, parser):
return False
return True
def ScanFile(self, path, parser):
"""
@ -32,4 +34,4 @@ class SourceScanner(object): @@ -32,4 +34,4 @@ class SourceScanner(object):
contents = ''
print('Failed reading file: %s, skipping content.' % path)
pass
parser.Parse(contents)
return parser.Parse(contents)

5
Tools/px_process_params.py

@ -115,7 +115,10 @@ def main(): @@ -115,7 +115,10 @@ def main():
# Scan directories, and parse the files
print("Scanning source path " + args.src_path)
scanner.ScanDir(args.src_path, parser)
if not scanner.ScanDir(args.src_path, parser):
sys.exit(1)
if not parser.Validate():
sys.exit(1)
param_groups = parser.GetParamGroups()
# Output to XML file

2
package.xml

@ -47,12 +47,14 @@ @@ -47,12 +47,14 @@
<build_depend>libmavconn</build_depend>
<build_depend>tf</build_depend>
<build_depend>rostest</build_depend>
<build_depend>mav_msgs</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>eigen</run_depend>
<run_depend>libmavconn</run_depend>
<run_depend>tf</run_depend>
<run_depend>mav_msgs</run_depend>
<!-- The export tag contains other, unspecified, tags -->

12
src/drivers/boards/aerocore/board_config.h

@ -112,6 +112,18 @@ __BEGIN_DECLS @@ -112,6 +112,18 @@ __BEGIN_DECLS
#define GPIO_GPIO10_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
#define GPIO_GPIO11_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
*/
#define ADC_CHANNELS (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13)
// ADC defines to be used in sensors.cpp to read from a particular channel
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#define ADC_AIRSPEED_VOLTAGE_CHANNEL ((uint8_t)(-1))
/* PWM
*
* Eight PWM outputs are configured.

12
src/drivers/boards/px4fmu-v1/board_config.h

@ -120,6 +120,18 @@ __BEGIN_DECLS @@ -120,6 +120,18 @@ __BEGIN_DECLS
#define PX4_I2C_OBDEV_PX4IO_BL 0x18
#define PX4_I2C_OBDEV_PX4IO 0x1a
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
*/
#define ADC_CHANNELS (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13)
// ADC defines to be used in sensors.cpp to read from a particular channel
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
/* User GPIOs
*
* GPIO0-1 are the buffered high-power GPIOs.

13
src/drivers/boards/px4fmu-v2/board_config.h

@ -146,6 +146,19 @@ __BEGIN_DECLS @@ -146,6 +146,19 @@ __BEGIN_DECLS
#define PX4_I2C_OBDEV_LED 0x55
#define PX4_I2C_OBDEV_HMC5883 0x1e
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
*/
#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15)
// ADC defines to be used in sensors.cpp to read from a particular channel
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
#define ADC_BATTERY_CURRENT_CHANNEL 3
#define ADC_5V_RAIL_SENSE 4
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
/* User GPIOs
*
* GPIO0-5 are the PWM servo outputs.

48
src/drivers/gps/gps.cpp

@ -310,7 +310,7 @@ GPS::task_main() @@ -310,7 +310,7 @@ GPS::task_main()
_report_gps_pos.cog_rad = 0.0f;
_report_gps_pos.vel_ned_valid = true;
//no time and satellite information simulated
/* no time and satellite information simulated */
if (!(_pub_blocked)) {
@ -351,28 +351,46 @@ GPS::task_main() @@ -351,28 +351,46 @@ GPS::task_main()
unlock();
/* the Ashtech driver lies about successful configuration and the
* MTK driver is not well tested, so we really only trust the UBX
* driver for an advance publication
*/
if (_Helper->configure(_baudrate) == 0) {
unlock();
//Publish initial report that we have access to a GPS
//Make sure to clear any stale data in case driver is reset
/* reset report */
memset(&_report_gps_pos, 0, sizeof(_report_gps_pos));
_report_gps_pos.timestamp_position = hrt_absolute_time();
_report_gps_pos.timestamp_variance = hrt_absolute_time();
_report_gps_pos.timestamp_velocity = hrt_absolute_time();
_report_gps_pos.timestamp_time = hrt_absolute_time();
if (!(_pub_blocked)) {
if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
if (_mode == GPS_DRIVER_MODE_UBX) {
/* Publish initial report that we have access to a GPS,
* but set all critical state fields to indicate we have
* no valid position lock
*/
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
_report_gps_pos.timestamp_time = hrt_absolute_time();
/* reset the timestamps for data, because we have no data yet */
_report_gps_pos.timestamp_position = 0;
_report_gps_pos.timestamp_variance = 0;
_report_gps_pos.timestamp_velocity = 0;
/* set a massive variance */
_report_gps_pos.eph = 10000.0f;
_report_gps_pos.epv = 10000.0f;
_report_gps_pos.fix_type = 0;
if (!(_pub_blocked)) {
if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
}
}
// GPS is obviously detected successfully, reset statistics
_Helper->reset_update_rates();
/* GPS is obviously detected successfully, reset statistics */
_Helper->reset_update_rates();
}
int helper_ret;
while ((helper_ret = _Helper->receive(TIMEOUT_5HZ)) > 0 && !_task_should_exit) {

15
src/drivers/stm32/adc/adc.cpp

@ -410,19 +410,8 @@ int @@ -410,19 +410,8 @@ int
adc_main(int argc, char *argv[])
{
if (g_adc == nullptr) {
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* XXX this hardcodes the default channel set for PX4FMUv1 - should be configurable */
g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
/* XXX this hardcodes the default channel set for PX4FMUv2 - should be configurable */
g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
(1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
#endif
#ifdef CONFIG_ARCH_BOARD_AEROCORE
/* XXX this hardcodes the default channel set for AeroCore - should be configurable */
g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
#endif
/* XXX this hardcodes the default channel set for the board in board_config.h - should be configurable */
g_adc = new ADC(ADC_CHANNELS);
if (g_adc == nullptr)
errx(1, "couldn't allocate the ADC driver");

1
src/modules/camera_trigger/camera_trigger_params.c

@ -83,7 +83,6 @@ PARAM_DEFINE_INT32(TRIG_POLARITY, 0); @@ -83,7 +83,6 @@ PARAM_DEFINE_INT32(TRIG_POLARITY, 0);
* integration.
*
* @unit milliseconds
* @default 4.0 ms
* @group Camera trigger
*/
PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 5.0f);

2
src/modules/commander/commander_params.c

@ -114,7 +114,7 @@ PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.2f); @@ -114,7 +114,7 @@ PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.2f);
*
* @group Battery Calibration
* @unit V
* @min 0.0f
* @min 0.0
*/
PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.07f);

2
src/modules/commander/mag_calibration.cpp

@ -226,7 +226,7 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta @@ -226,7 +226,7 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta
* for a good result, so we're not constraining the user more than we have to.
*/
hrt_abstime detection_deadline = hrt_absolute_time() + worker_data->calibration_interval_perside_useconds;
hrt_abstime detection_deadline = hrt_absolute_time() + worker_data->calibration_interval_perside_useconds * 2;
hrt_abstime last_gyro = 0;
float gyro_x_integral = 0.0f;
float gyro_y_integral = 0.0f;

8
src/modules/mavlink/mavlink_main.cpp

@ -1597,7 +1597,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1597,7 +1597,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("GPS_RAW_INT", 1.0f);
configure_stream("GLOBAL_POSITION_INT", 3.0f);
configure_stream("LOCAL_POSITION_NED", 3.0f);
configure_stream("RC_CHANNELS_RAW", 1.0f);
configure_stream("RC_CHANNELS", 1.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
configure_stream("ATTITUDE_TARGET", 3.0f);
configure_stream("DISTANCE_SENSOR", 0.5f);
@ -1606,7 +1606,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1606,7 +1606,7 @@ Mavlink::task_main(int argc, char *argv[])
case MAVLINK_MODE_ONBOARD:
configure_stream("SYS_STATUS", 1.0f);
configure_stream("ATTITUDE", 50.0f);
configure_stream("ATTITUDE", 250.0f);
configure_stream("HIGHRES_IMU", 50.0f);
configure_stream("GPS_RAW_INT", 5.0f);
configure_stream("GLOBAL_POSITION_INT", 50.0f);
@ -1617,7 +1617,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1617,7 +1617,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
configure_stream("DISTANCE_SENSOR", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("RC_CHANNELS_RAW", 20.0f);
configure_stream("RC_CHANNELS", 20.0f);
configure_stream("VFR_HUD", 10.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("TIMESYNC", 10.0f);
@ -1634,7 +1634,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1634,7 +1634,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("ATTITUDE_TARGET", 10.0f);
configure_stream("BATTERY_STATUS", 1.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("RC_CHANNELS_RAW", 5.0f);
configure_stream("RC_CHANNELS", 5.0f);
break;
default:

21
src/modules/mavlink/mavlink_messages.cpp

@ -1914,33 +1914,32 @@ protected: @@ -1914,33 +1914,32 @@ protected:
};
class MavlinkStreamRCChannelsRaw : public MavlinkStream
class MavlinkStreamRCChannels : public MavlinkStream
{
public:
const char *get_name() const
{
return MavlinkStreamRCChannelsRaw::get_name_static();
return MavlinkStreamRCChannels::get_name_static();
}
static const char *get_name_static()
{
return "RC_CHANNELS_RAW";
return "RC_CHANNELS";
}
uint8_t get_id()
{
return MAVLINK_MSG_ID_RC_CHANNELS_RAW;
return MAVLINK_MSG_ID_RC_CHANNELS;
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
return new MavlinkStreamRCChannelsRaw(mavlink);
return new MavlinkStreamRCChannels(mavlink);
}
unsigned get_size()
{
return _rc_sub->is_published() ? ((RC_INPUT_MAX_CHANNELS / 8) * (MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) +
MAVLINK_MSG_ID_RC_CHANNELS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
return _rc_sub->is_published() ? (MAVLINK_MSG_ID_RC_CHANNELS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
}
private:
@ -1948,11 +1947,11 @@ private: @@ -1948,11 +1947,11 @@ private:
uint64_t _rc_time;
/* do not allow top copying this class */
MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &);
MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &);
MavlinkStreamRCChannels(MavlinkStreamRCChannels &);
MavlinkStreamRCChannels& operator = (const MavlinkStreamRCChannels &);
protected:
explicit MavlinkStreamRCChannelsRaw(Mavlink *mavlink) : MavlinkStream(mavlink),
explicit MavlinkStreamRCChannels(Mavlink *mavlink) : MavlinkStream(mavlink),
_rc_sub(_mavlink->add_orb_subscription(ORB_ID(input_rc))),
_rc_time(0)
{}
@ -2358,7 +2357,7 @@ const StreamListItem *streams_list[] = { @@ -2358,7 +2357,7 @@ const StreamListItem *streams_list[] = {
new StreamListItem(&MavlinkStreamPositionTargetGlobalInt::new_instance, &MavlinkStreamPositionTargetGlobalInt::get_name_static),
new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static),
new StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static),
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
new StreamListItem(&MavlinkStreamRCChannels::new_instance, &MavlinkStreamRCChannels::get_name_static),
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
new StreamListItem(&MavlinkStreamOpticalFlowRad::new_instance, &MavlinkStreamOpticalFlowRad::get_name_static),
new StreamListItem(&MavlinkStreamActuatorControlTarget<0>::new_instance, &MavlinkStreamActuatorControlTarget<0>::get_name_static),

63
src/modules/navigator/mission.cpp

@ -70,8 +70,8 @@ Mission::Mission(Navigator *navigator, const char *name) : @@ -70,8 +70,8 @@ Mission::Mission(Navigator *navigator, const char *name) :
_param_dist_1wp(this, "MIS_DIST_1WP", false),
_param_altmode(this, "MIS_ALTMODE", false),
_param_yawmode(this, "MIS_YAWMODE", false),
_onboard_mission({0}),
_offboard_mission({0}),
_onboard_mission{},
_offboard_mission{},
_current_onboard_mission_index(-1),
_current_offboard_mission_index(-1),
_need_takeoff(true),
@ -110,32 +110,29 @@ Mission::on_inactive() @@ -110,32 +110,29 @@ Mission::on_inactive()
update_offboard_mission();
}
/* check if the home position became valid in the meantime */
if ((_mission_type == MISSION_TYPE_NONE || _mission_type == MISSION_TYPE_OFFBOARD) &&
!_home_inited && _navigator->home_position_valid()) {
} else {
/* load missions from storage */
mission_s mission_state;
dm_item_t dm_current = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id);
dm_lock(DM_KEY_MISSION_STATE);
_navigator->get_mission_result()->valid = _missionFeasiblityChecker.checkMissionFeasible(_navigator->get_mavlink_fd(), _navigator->get_vstatus()->is_rotary_wing,
dm_current, (size_t) _offboard_mission.count, _navigator->get_geofence(),
_navigator->get_home_position()->alt, _navigator->home_position_valid(),
_navigator->get_global_position()->lat, _navigator->get_global_position()->lon,
_param_dist_1wp.get(), _navigator->get_mission_result()->warning);
/* read current state */
int read_res = dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s));
_navigator->increment_mission_instance_count();
_navigator->set_mission_result_updated();
dm_unlock(DM_KEY_MISSION_STATE);
_home_inited = true;
if (read_res == sizeof(mission_s)) {
_offboard_mission.dataman_id = mission_state.dataman_id;
_offboard_mission.count = mission_state.count;
_current_offboard_mission_index = mission_state.current_seq;
}
} else {
/* read mission topics on initialization */
_inited = true;
update_onboard_mission();
update_offboard_mission();
}
check_mission_valid();
/* require takeoff after non-loiter or landing */
if (!_navigator->get_can_loiter_at_sp() || _navigator->get_vstatus()->condition_landed) {
_need_takeoff = true;
@ -151,6 +148,8 @@ Mission::on_activation() @@ -151,6 +148,8 @@ Mission::on_activation()
void
Mission::on_active()
{
check_mission_valid();
/* check if anything has changed */
bool onboard_updated = false;
orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated);
@ -272,6 +271,8 @@ Mission::update_offboard_mission() @@ -272,6 +271,8 @@ Mission::update_offboard_mission()
_offboard_mission.count = 0;
_offboard_mission.current_seq = 0;
_current_offboard_mission_index = 0;
warnx("mission check failed");
}
set_current_offboard_mission_item();
@ -652,6 +653,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s @@ -652,6 +653,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s
if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) {
/* mission item index out of bounds */
mavlink_log_critical(_navigator->get_mavlink_fd(), "[wpm] err: index: %d, max: %d", *mission_index_ptr, (int)mission->count);
return false;
}
@ -795,3 +797,26 @@ Mission::set_mission_finished() @@ -795,3 +797,26 @@ Mission::set_mission_finished()
_navigator->get_mission_result()->finished = true;
_navigator->set_mission_result_updated();
}
bool
Mission::check_mission_valid()
{
/* check if the home position became valid in the meantime */
if (!_home_inited && _navigator->home_position_valid()) {
dm_item_t dm_current = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id);
_navigator->get_mission_result()->valid = _missionFeasiblityChecker.checkMissionFeasible(_navigator->get_mavlink_fd(), _navigator->get_vstatus()->is_rotary_wing,
dm_current, (size_t) _offboard_mission.count, _navigator->get_geofence(),
_navigator->get_home_position()->alt, _navigator->home_position_valid(),
_navigator->get_global_position()->lat, _navigator->get_global_position()->lon,
_param_dist_1wp.get(), _navigator->get_mission_result()->warning);
_navigator->increment_mission_instance_count();
_navigator->set_mission_result_updated();
_home_inited = true;
}
return _navigator->get_mission_result()->valid;
}

8
src/modules/navigator/mission.h

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -39,6 +39,7 @@ @@ -39,6 +39,7 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Ban Siesta <bansiesta@gmail.com>
* @author Lorenz Meier <lorenz@px4.io>
*/
#ifndef NAVIGATOR_MISSION_H
@ -165,6 +166,11 @@ private: @@ -165,6 +166,11 @@ private:
*/
void set_mission_finished();
/**
* Check wether a mission is ready to go
*/
bool check_mission_valid();
control::BlockParamInt _param_onboard_enabled;
control::BlockParamFloat _param_takeoff_alt;
control::BlockParamFloat _param_dist_1wp;

22
src/modules/sensors/sensors.cpp

@ -46,6 +46,8 @@ @@ -46,6 +46,8 @@
* @author Anton Babushkin <anton@px4.io>
*/
#include <board_config.h>
#include <px4_config.h>
#include <px4_tasks.h>
#include <px4_posix.h>
@ -111,26 +113,10 @@ @@ -111,26 +113,10 @@
* IO:
* IN4 - servo supply rail
* IN5 - analog RSSI
*
* The channel definitions (e.g., ADC_BATTERY_VOLTAGE_CHANNEL, ADC_BATTERY_CURRENT_CHANNEL, and ADC_AIRSPEED_VOLTAGE_CHANNEL) are defined in board_config.h
*/
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
#define ADC_BATTERY_CURRENT_CHANNEL 3
#define ADC_5V_RAIL_SENSE 4
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
#endif
#ifdef CONFIG_ARCH_BOARD_AEROCORE
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#define ADC_AIRSPEED_VOLTAGE_CHANNEL ((uint8_t)(-1))
#endif
#define BATT_V_LOWPASS 0.001f
#define BATT_V_IGNORE_THRESHOLD 2.5f

6
src/platforms/qurt/px4_layer/main.cpp

@ -100,7 +100,11 @@ static void process_commands(map<string,px4_main_t> &apps, const char *cmds) @@ -100,7 +100,11 @@ static void process_commands(map<string,px4_main_t> &apps, const char *cmds)
// This is added because it is a parameter used by commander, yet created by mavlink. Since mavlink is not
// running on QURT, we need to manually define it so it is available to commander. "2" is for quadrotor.
PARAM_DEFINE_INT32(MAV_TYPE,2);
// Following is hack to prevent duplicate parameter definition error in param parser
/**
* @board QuRT_App
*/
PARAM_DEFINE_INT32(MAV_TYPE,2);
// Eat leading whitespace
eat_whitespace(b, i);

3
src/platforms/ros/nodes/position_estimator/position_estimator.cpp

@ -54,6 +54,7 @@ PositionEstimator::PositionEstimator() : @@ -54,6 +54,7 @@ PositionEstimator::PositionEstimator() :
_vehicle_position_pub(_n.advertise<px4::vehicle_local_position>("vehicle_local_position", 1)),
_startup_time(1)
{
_n.getParam("vehicle_model", _model_name);
}
void PositionEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstPtr &msg)
@ -68,7 +69,7 @@ void PositionEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstP @@ -68,7 +69,7 @@ void PositionEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstP
//XXX: maybe a more clever approach would be to do this not on every loop, need to check if and when
//gazebo rearranges indexes.
for (std::vector<std::string>::const_iterator it = msg->name.begin(); it != msg->name.end(); ++it) {
if (*it == "iris" || *it == "ardrone") {
if (*it == _model_name) {
index = it - msg->name.begin();
break;
}

2
src/platforms/ros/nodes/position_estimator/position_estimator.h

@ -57,6 +57,6 @@ protected: @@ -57,6 +57,6 @@ protected:
ros::Publisher _vehicle_position_pub;
uint64_t _startup_time;
std::string _model_name;
};

Loading…
Cancel
Save