Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create and use AP_PERIPH_RPM_ENABLED and AP_PERIPH_RPM_STREAM_ENABLED #29216

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,7 @@ void AP_Periph_FW::init()
nmea.init();
#endif

#ifdef HAL_PERIPH_ENABLE_RPM
#if AP_PERIPH_RPM_ENABLED
rpm_sensor.init();
#endif

Expand Down Expand Up @@ -522,7 +522,7 @@ void AP_Periph_FW::update()
temperature_sensor.update();
#endif

#ifdef HAL_PERIPH_ENABLE_RPM
#if AP_PERIPH_RPM_ENABLED
if (now - rpm_last_update_ms >= 100) {
rpm_last_update_ms = now;
rpm_sensor.update();
Expand Down
10 changes: 5 additions & 5 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,8 @@
#endif
#endif

#if defined(HAL_PERIPH_ENABLE_RPM_STREAM) && !defined(HAL_PERIPH_ENABLE_RPM)
#error "HAL_PERIPH_ENABLE_RPM_STREAM requires HAL_PERIPH_ENABLE_RPM"
#if AP_PERIPH_RPM_STREAM_ENABLED && !AP_PERIPH_RPM_ENABLED
#error "AP_PERIPH_RPM_STREAM_ENABLED requires AP_PERIPH_RPM_ENABLED"
#endif

#ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED
Expand Down Expand Up @@ -239,15 +239,15 @@ class AP_Periph_FW {
AP_InertialSensor imu;
#endif

#ifdef HAL_PERIPH_ENABLE_RPM
#if AP_PERIPH_RPM_ENABLED
AP_RPM rpm_sensor;
uint32_t rpm_last_update_ms;
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_PERIPH_RPM_STREAM_ENABLED
void rpm_sensor_send();
uint32_t rpm_last_send_ms;
uint8_t rpm_last_sent_index;
#endif
#endif // HAL_PERIPH_ENABLE_RPM
#endif // AP_PERIPH_RPM_ENABLED

#if AP_PERIPH_BATTERY_ENABLED
void handle_battery_failsafe(const char* type_str, const int8_t action) { }
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -625,7 +625,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(networking_periph, "NET_", Networking_Periph),
#endif

#ifdef HAL_PERIPH_ENABLE_RPM
#if AP_PERIPH_RPM_ENABLED
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT(rpm_sensor, "RPM", AP_RPM),
Expand Down Expand Up @@ -701,7 +701,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @User: Standard
GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS),

#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_PERIPH_RPM_STREAM_ENABLED
// @Param: RPM_MSG_RATE
// @DisplayName: RPM sensor message rate
// @Description: This is the rate RPM sensor data is sent in Hz. Zero means no send. Each sensor with a set ID is sent in turn.
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ class Parameters {
AP_Int8 temperature_msg_rate;
#endif

#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_PERIPH_RPM_STREAM_ENABLED
AP_Int16 rpm_msg_rate;
#endif

Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1966,7 +1966,7 @@ void AP_Periph_FW::can_update()
#ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE
temperature_sensor_update();
#endif
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_PERIPH_RPM_STREAM_ENABLED
rpm_sensor_send();
#endif
}
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/rpm.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_PERIPH_RPM_STREAM_ENABLED

#include <dronecan_msgs.h>

Expand Down Expand Up @@ -52,4 +52,4 @@ void AP_Periph_FW::rpm_sensor_send(void)
}
}

#endif // HAL_PERIPH_ENABLE_RPM_STREAM
#endif // AP_PERIPH_RPM_STREAM_ENABLED
5 changes: 3 additions & 2 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -959,8 +959,9 @@ def configure_env(self, cfg, env):
AP_PERIPH_BATTERY_ENABLED = 1,
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
HAL_PERIPH_ENABLE_EFI = 1,
HAL_PERIPH_ENABLE_RPM = 1,
HAL_PERIPH_ENABLE_RPM_STREAM = 1,
AP_PERIPH_RPM_ENABLED = 1,
AP_PERIPH_RPM_STREAM_ENABLED = 1,
AP_RPM_STREAM_ENABLED = 1,
HAL_PERIPH_ENABLE_RC_OUT = 1,
HAL_PERIPH_ENABLE_ADSB = 1,
HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1,
Expand Down
18 changes: 17 additions & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,12 @@
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#error "Change 'define HAL_PERIPH_ENABLE_RANGEFINDER' to 'define AP_PERIPH_RANGEFINDER_ENABLED 1'"
#endif
#ifdef HAL_PERIPH_ENABLE_RPM
#error "Change 'define HAL_PERIPH_ENABLE_RPM' to 'define AP_PERIPH_RPM_ENABLED 1'"
#endif
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#error "Change 'define HAL_PERIPH_ENABLE_RPM_STREAM' to 'define AP_PERIPH_RPM_STREAM_ENABLED 1'"
#endif

/*
* defaults for various AP_Periph features:
Expand All @@ -206,6 +212,12 @@
#ifndef AP_PERIPH_RANGEFINDER_ENABLED
#define AP_PERIPH_RANGEFINDER_ENABLED 0
#endif
#ifndef AP_PERIPH_RPM_ENABLED
#define AP_PERIPH_RPM_ENABLED 0
#endif
#ifndef AP_PERIPH_RPM_STREAM_ENABLED
#define AP_PERIPH_RPM_STREAM_ENABLED AP_PERIPH_RPM_ENABLED
#endif

/*
* turning on of ArduPilot features based on which AP_Periph features
Expand All @@ -217,6 +229,7 @@
#define AP_COMPASS_ENABLED AP_PERIPH_MAG_ENABLED
#define AP_BARO_ENABLED AP_PERIPH_BARO_ENABLED
#define AP_RANGEFINDER_ENABLED AP_PERIPH_RANGEFINDER_ENABLED
#define AP_RPM_ENABLED AP_PERIPH_RPM_ENABLED

/*
* GPS Backends - we selectively turn backends on.
Expand Down Expand Up @@ -402,14 +415,17 @@
#define AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED 0
#endif

#define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM)
#define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN)
#define AP_RTC_ENABLED defined(HAL_PERIPH_ENABLE_RTC)
#define HAL_VISUALODOM_ENABLED defined(HAL_PERIPH_ENABLE_VISUALODOM)
#define AP_INERTIALSENSOR_ENABLED defined(HAL_PERIPH_ENABLE_IMU)
#define AP_INERTIALSENSOR_ALLOW_NO_SENSORS defined(HAL_PERIPH_ENABLE_IMU)
#define AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED 0

#ifndef AP_RPM_STREAM_ENABLED
#define AP_RPM_STREAM_ENABLED AP_PERIPH_RPM_STREAM_ENABLED
#endif

#ifndef AP_BOOTLOADER_ALWAYS_ERASE
#define AP_BOOTLOADER_ALWAYS_ERASE 1
#endif
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -325,7 +325,7 @@ void AP_RPM::Log_RPM() const
}
#endif

#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_RPM_STREAM_ENABLED
// Return the sensor id to use for streaming over DroneCAN, negative number disables
int8_t AP_RPM::get_dronecan_sensor_id(uint8_t instance) const
{
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ class AP_RPM
// check settings are valid
bool arming_checks(size_t buflen, char *buffer) const;

#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_RPM_STREAM_ENABLED
// Return the sensor id to use for streaming over DroneCAN, negative number disables
int8_t get_dronecan_sensor_id(uint8_t instance) const;
#endif
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = {
AP_GROUPINFO("ESC_INDEX", 8, AP_RPM_Params, esc_telem_outbound_index, 0),
#endif

#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM)
#if AP_RPM_DRONECAN_ENABLED || AP_RPM_STREAM_ENABLED
// @Param: DC_ID
// @DisplayName: DroneCAN Sensor ID
// @Description: DroneCAN sensor ID to assign to this backend
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM_Params.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class AP_RPM_Params {
#if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED
AP_Int8 esc_telem_outbound_index;
#endif
#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM)
#if AP_RPM_DRONECAN_ENABLED || AP_RPM_STREAM_ENABLED
AP_Int8 dronecan_sensor_id;
#endif
static const struct AP_Param::GroupInfo var_info[];
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_RPM/AP_RPM_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,3 +53,7 @@
#if AP_RPM_DRONECAN_ENABLED && !HAL_ENABLE_DRONECAN_DRIVERS
#error AP_RPM_DRONECAN_ENABLED requires HAL_ENABLE_DRONECAN_DRIVERS
#endif

#ifndef AP_RPM_STREAM_ENABLED
#define AP_RPM_STREAM_ENABLED 0
#endif
Loading