mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-29 02:24:10 +08:00
commit
178a3e8567
@ -419,16 +419,6 @@ then
|
||||
|
||||
mavlink start $MAVLINK_FLAGS
|
||||
|
||||
#
|
||||
# Start the datamanager
|
||||
#
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the navigator
|
||||
#
|
||||
navigator start
|
||||
|
||||
#
|
||||
# Sensors, Logging, GPS
|
||||
#
|
||||
@ -550,6 +540,16 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the datamanager
|
||||
#
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the navigator
|
||||
#
|
||||
navigator start
|
||||
|
||||
#
|
||||
# Generic setup (autostart ID not found)
|
||||
#
|
||||
|
||||
@ -504,8 +504,8 @@ CONFIG_MTD_BYTE_WRITE=y
|
||||
#
|
||||
# USART1 Configuration
|
||||
#
|
||||
CONFIG_USART1_RXBUFSIZE=512
|
||||
CONFIG_USART1_TXBUFSIZE=512
|
||||
CONFIG_USART1_RXBUFSIZE=256
|
||||
CONFIG_USART1_TXBUFSIZE=128
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_BITS=8
|
||||
CONFIG_USART1_PARITY=0
|
||||
@ -528,8 +528,8 @@ CONFIG_USART2_OFLOWCONTROL=y
|
||||
#
|
||||
# UART5 Configuration
|
||||
#
|
||||
CONFIG_UART5_RXBUFSIZE=512
|
||||
CONFIG_UART5_TXBUFSIZE=512
|
||||
CONFIG_UART5_RXBUFSIZE=256
|
||||
CONFIG_UART5_TXBUFSIZE=128
|
||||
CONFIG_UART5_BAUD=57600
|
||||
CONFIG_UART5_BITS=8
|
||||
CONFIG_UART5_PARITY=0
|
||||
@ -540,8 +540,8 @@ CONFIG_UART5_2STOP=0
|
||||
#
|
||||
# USART6 Configuration
|
||||
#
|
||||
CONFIG_USART6_RXBUFSIZE=512
|
||||
CONFIG_USART6_TXBUFSIZE=512
|
||||
CONFIG_USART6_RXBUFSIZE=128
|
||||
CONFIG_USART6_TXBUFSIZE=64
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_BITS=8
|
||||
CONFIG_USART6_PARITY=0
|
||||
|
||||
@ -194,6 +194,26 @@ private:
|
||||
|
||||
bool systemstate_run;
|
||||
|
||||
int vehicle_status_sub_fd;
|
||||
int vehicle_control_mode_sub_fd;
|
||||
int vehicle_gps_position_sub_fd;
|
||||
int actuator_armed_sub_fd;
|
||||
int safety_sub_fd;
|
||||
|
||||
int num_of_cells;
|
||||
int detected_cells_runcount;
|
||||
|
||||
int t_led_color[8];
|
||||
int t_led_blink;
|
||||
int led_thread_runcount;
|
||||
int led_interval;
|
||||
|
||||
bool topic_initialized;
|
||||
bool detected_cells_blinked;
|
||||
bool led_thread_ready;
|
||||
|
||||
int num_of_used_sats;
|
||||
|
||||
void setLEDColor(int ledcolor);
|
||||
static void led_trampoline(void *arg);
|
||||
void led();
|
||||
@ -265,7 +285,22 @@ BlinkM::BlinkM(int bus, int blinkm) :
|
||||
led_color_7(LED_OFF),
|
||||
led_color_8(LED_OFF),
|
||||
led_blink(LED_NOBLINK),
|
||||
systemstate_run(false)
|
||||
systemstate_run(false),
|
||||
vehicle_status_sub_fd(-1),
|
||||
vehicle_control_mode_sub_fd(-1),
|
||||
vehicle_gps_position_sub_fd(-1),
|
||||
actuator_armed_sub_fd(-1),
|
||||
safety_sub_fd(-1),
|
||||
num_of_cells(0),
|
||||
detected_cells_runcount(0),
|
||||
t_led_color({0}),
|
||||
t_led_blink(0),
|
||||
led_thread_runcount(0),
|
||||
led_interval(1000),
|
||||
topic_initialized(false),
|
||||
detected_cells_blinked(false),
|
||||
led_thread_ready(true),
|
||||
num_of_used_sats(0)
|
||||
{
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
}
|
||||
@ -382,31 +417,6 @@ void
|
||||
BlinkM::led()
|
||||
{
|
||||
|
||||
static int vehicle_status_sub_fd;
|
||||
static int vehicle_control_mode_sub_fd;
|
||||
static int vehicle_gps_position_sub_fd;
|
||||
static int actuator_armed_sub_fd;
|
||||
static int safety_sub_fd;
|
||||
|
||||
static int num_of_cells = 0;
|
||||
static int detected_cells_runcount = 0;
|
||||
|
||||
static int t_led_color[8] = { 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
static int t_led_blink = 0;
|
||||
static int led_thread_runcount=0;
|
||||
static int led_interval = 1000;
|
||||
|
||||
static int no_data_vehicle_status = 0;
|
||||
static int no_data_vehicle_control_mode = 0;
|
||||
static int no_data_actuator_armed = 0;
|
||||
static int no_data_vehicle_gps_position = 0;
|
||||
|
||||
static bool topic_initialized = false;
|
||||
static bool detected_cells_blinked = false;
|
||||
static bool led_thread_ready = true;
|
||||
|
||||
int num_of_used_sats = 0;
|
||||
|
||||
if(!topic_initialized) {
|
||||
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
|
||||
orb_set_interval(vehicle_status_sub_fd, 250);
|
||||
@ -494,6 +504,11 @@ BlinkM::led()
|
||||
|
||||
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
|
||||
|
||||
int no_data_vehicle_status = 0;
|
||||
int no_data_vehicle_control_mode = 0;
|
||||
int no_data_actuator_armed = 0;
|
||||
int no_data_vehicle_gps_position = 0;
|
||||
|
||||
if (new_data_vehicle_status) {
|
||||
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub_fd, &vehicle_status_raw);
|
||||
no_data_vehicle_status = 0;
|
||||
|
||||
@ -158,6 +158,7 @@ private:
|
||||
int _class_instance;
|
||||
|
||||
orb_advert_t _mag_topic;
|
||||
orb_advert_t _subsystem_pub;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
@ -324,7 +325,9 @@ HMC5883::HMC5883(int bus) :
|
||||
_reports(nullptr),
|
||||
_range_scale(0), /* default range scale from counts to gauss */
|
||||
_range_ga(1.3f),
|
||||
_collect_phase(false),
|
||||
_mag_topic(-1),
|
||||
_subsystem_pub(-1),
|
||||
_class_instance(-1),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
|
||||
@ -1137,13 +1140,12 @@ int HMC5883::check_calibration()
|
||||
true,
|
||||
_calibrated,
|
||||
SUBSYSTEM_TYPE_MAG};
|
||||
static orb_advert_t pub = -1;
|
||||
|
||||
if (!(_pub_blocked)) {
|
||||
if (pub > 0) {
|
||||
orb_publish(ORB_ID(subsystem_info), pub, &info);
|
||||
if (_subsystem_pub > 0) {
|
||||
orb_publish(ORB_ID(subsystem_info), _subsystem_pub, &info);
|
||||
} else {
|
||||
pub = orb_advertise(ORB_ID(subsystem_info), &info);
|
||||
_subsystem_pub = orb_advertise(ORB_ID(subsystem_info), &info);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -51,6 +51,8 @@
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
/* The board is very roughly 5 deg warmer than the surrounding air */
|
||||
#define BOARD_TEMP_OFFSET_DEG 5
|
||||
|
||||
@ -62,7 +64,6 @@ static int _airspeed_sub = -1;
|
||||
static int _esc_sub = -1;
|
||||
|
||||
static orb_advert_t _esc_pub;
|
||||
struct esc_status_s _esc;
|
||||
|
||||
static bool _home_position_set = false;
|
||||
static double _home_lat = 0.0d;
|
||||
@ -82,8 +83,6 @@ init_sub_messages(void)
|
||||
void
|
||||
init_pub_messages(void)
|
||||
{
|
||||
memset(&_esc, 0, sizeof(_esc));
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
|
||||
}
|
||||
|
||||
void
|
||||
@ -106,23 +105,26 @@ publish_gam_message(const uint8_t *buffer)
|
||||
size_t size = sizeof(msg);
|
||||
memset(&msg, 0, size);
|
||||
memcpy(&msg, buffer, size);
|
||||
struct esc_status_s esc;
|
||||
memset(&esc, 0, sizeof(esc));
|
||||
|
||||
// Publish it.
|
||||
esc.timestamp = hrt_absolute_time();
|
||||
esc.esc_count = 1;
|
||||
esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
|
||||
|
||||
esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
|
||||
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
|
||||
esc.esc[0].esc_temperature = msg.temperature1 - 20;
|
||||
esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
|
||||
esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
|
||||
|
||||
/* announce the esc if needed, just publish else */
|
||||
if (_esc_pub > 0) {
|
||||
orb_publish(ORB_ID(esc_status), _esc_pub, &_esc);
|
||||
orb_publish(ORB_ID(esc_status), _esc_pub, &esc);
|
||||
} else {
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &esc);
|
||||
}
|
||||
|
||||
// Publish it.
|
||||
_esc.esc_count = 1;
|
||||
_esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
|
||||
|
||||
_esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
|
||||
_esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
|
||||
_esc.esc[0].esc_temperature = msg.temperature1 - 20;
|
||||
_esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
|
||||
_esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@ -92,8 +92,20 @@
|
||||
#define MOTOR_SPINUP_COUNTER 30
|
||||
#define ESC_UORB_PUBLISH_DELAY 500000
|
||||
|
||||
|
||||
|
||||
struct MotorData_t {
|
||||
unsigned int Version; // the version of the BL (0 = old)
|
||||
unsigned int SetPoint; // written by attitude controller
|
||||
unsigned int SetPointLowerBits; // for higher Resolution of new BLs
|
||||
float SetPoint_PX4; // Values from PX4
|
||||
unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
|
||||
unsigned int ReadMode; // select data to read
|
||||
unsigned short RawPwmValue; // length of PWM pulse
|
||||
// the following bytes must be exactly in that order!
|
||||
unsigned int Current; // in 0.1 A steps, read back from BL
|
||||
unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
|
||||
unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
|
||||
unsigned int RoundCount;
|
||||
};
|
||||
|
||||
class MK : public device::I2C
|
||||
{
|
||||
@ -154,6 +166,8 @@ private:
|
||||
|
||||
actuator_controls_s _controls;
|
||||
|
||||
MotorData_t Motor[MAX_MOTORS];
|
||||
|
||||
static void task_main_trampoline(int argc, char *argv[]);
|
||||
void task_main();
|
||||
|
||||
@ -195,24 +209,6 @@ const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
int addrTranslator[] = {0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
struct MotorData_t {
|
||||
unsigned int Version; // the version of the BL (0 = old)
|
||||
unsigned int SetPoint; // written by attitude controller
|
||||
unsigned int SetPointLowerBits; // for higher Resolution of new BLs
|
||||
float SetPoint_PX4; // Values from PX4
|
||||
unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
|
||||
unsigned int ReadMode; // select data to read
|
||||
unsigned short RawPwmValue; // length of PWM pulse
|
||||
// the following bytes must be exactly in that order!
|
||||
unsigned int Current; // in 0.1 A steps, read back from BL
|
||||
unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
|
||||
unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
|
||||
unsigned int RoundCount;
|
||||
};
|
||||
|
||||
MotorData_t Motor[MAX_MOTORS];
|
||||
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
|
||||
@ -354,6 +354,9 @@ __EXPORT uint16_t ppm_frame_length = 0;
|
||||
__EXPORT unsigned ppm_decoded_channels = 0;
|
||||
__EXPORT uint64_t ppm_last_valid_decode = 0;
|
||||
|
||||
#define PPM_DEBUG 0
|
||||
|
||||
#if PPM_DEBUG
|
||||
/* PPM edge history */
|
||||
__EXPORT uint16_t ppm_edge_history[32];
|
||||
unsigned ppm_edge_next;
|
||||
@ -361,6 +364,7 @@ unsigned ppm_edge_next;
|
||||
/* PPM pulse history */
|
||||
__EXPORT uint16_t ppm_pulse_history[32];
|
||||
unsigned ppm_pulse_next;
|
||||
#endif
|
||||
|
||||
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
|
||||
|
||||
@ -455,10 +459,12 @@ hrt_ppm_decode(uint32_t status)
|
||||
/* how long since the last edge? - this handles counter wrapping implicitely. */
|
||||
width = count - ppm.last_edge;
|
||||
|
||||
#if PPM_DEBUG
|
||||
ppm_edge_history[ppm_edge_next++] = width;
|
||||
|
||||
if (ppm_edge_next >= 32)
|
||||
ppm_edge_next = 0;
|
||||
#endif
|
||||
|
||||
/*
|
||||
* if this looks like a start pulse, then push the last set of values
|
||||
@ -546,10 +552,12 @@ hrt_ppm_decode(uint32_t status)
|
||||
interval = count - ppm.last_mark;
|
||||
ppm.last_mark = count;
|
||||
|
||||
#if PPM_DEBUG
|
||||
ppm_pulse_history[ppm_pulse_next++] = interval;
|
||||
|
||||
if (ppm_pulse_next >= 32)
|
||||
ppm_pulse_next = 0;
|
||||
#endif
|
||||
|
||||
/* if the mark-mark timing is out of bounds, abandon the frame */
|
||||
if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
|
||||
|
||||
@ -727,9 +727,9 @@ int Mavlink::mavlink_pm_send_param(param_t param)
|
||||
if (param == PARAM_INVALID) { return 1; }
|
||||
|
||||
/* buffers for param transmission */
|
||||
static char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
|
||||
char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
|
||||
float val_buf;
|
||||
static mavlink_message_t tx_msg;
|
||||
mavlink_message_t tx_msg;
|
||||
|
||||
/* query parameter type */
|
||||
param_type_t type = param_type(param);
|
||||
|
||||
@ -100,8 +100,8 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
|
||||
/* Check if all mission items are inside the geofence (if we have a valid geofence) */
|
||||
if (geofence.valid()) {
|
||||
for (size_t i = 0; i < nMissionItems; i++) {
|
||||
static struct mission_item_s missionitem;
|
||||
const ssize_t len = sizeof(struct mission_item_s);
|
||||
struct mission_item_s missionitem;
|
||||
const ssize_t len = sizeof(missionitem);
|
||||
|
||||
if (dm_read(dm_current, i, &missionitem, len) != len) {
|
||||
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
|
||||
@ -125,8 +125,8 @@ bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size
|
||||
|
||||
|
||||
for (size_t i = 0; i < nMissionItems; i++) {
|
||||
static struct mission_item_s missionitem;
|
||||
const ssize_t len = sizeof(struct mission_item_s);
|
||||
struct mission_item_s missionitem;
|
||||
const ssize_t len = sizeof(missionitem);
|
||||
if (dm_read(dm_current, i, &missionitem, len) != len) {
|
||||
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
|
||||
return false;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user