Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
  • Loading branch information
bugobliterator committed Nov 27, 2024
1 parent 6d41070 commit de1caab
Show file tree
Hide file tree
Showing 20 changed files with 53 additions and 14 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_AccelCal/AP_AccelCal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -362,7 +362,7 @@ bool AP_AccelCal::client_active(uint8_t client_num)
return (bool)_clients[client_num]->_acal_get_calibrator(0);
}

#if HAL_GCS_ENABLED
#if HAL_GCS_ENABLED || defined(GCS_MAVLINK)
void AP_AccelCal::handle_command_ack(const mavlink_command_ack_t &packet)
{
if (!_waiting_for_mavlink_ack) {
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_AccelCal/AP_AccelCal.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@
#endif
#endif

#include <GCS_MAVLink/GCS.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

#include "AccelCalibrator.h"

#define AP_ACCELCAL_MAX_NUM_CLIENTS 4
Expand Down Expand Up @@ -45,7 +47,7 @@ class AP_AccelCal {
// interface to the clients for registration
static void register_client(AP_AccelCal_Client* client);

#if HAL_GCS_ENABLED
#if HAL_GCS_ENABLED || defined(GCS_MAVLINK)
void handle_command_ack(const mavlink_command_ack_t &packet);
#endif

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo Compass::var_info[] = {
// index 0 was used for the old orientation matrix

#ifndef HAL_BUILD_AP_PERIPH
#if !defined(HAL_BUILD_AP_PERIPH) && !COMPASS_CAL_ENABLED
// @Param: OFS_X
// @DisplayName: Compass offsets in milligauss on the X axis
// @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_MSP/msp.h>
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_Calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,7 @@ bool Compass::_accept_calibration_mask(uint8_t mask)
return success;
}

#if HAL_GCS_ENABLED
#if HAL_GCS_ENABLED || defined(GCS_MAVLINK)
bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link)
{
const mavlink_channel_t chan = link.get_chan();
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_DAL/AP_DAL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,9 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
#if AP_OPTICALFLOW_ENABLED
_RFRN.opticalflow_enabled = AP::opticalflow() && AP::opticalflow()->enabled();
#endif
#if AP_WHEELENCODER_ENABLED
_RFRN.wheelencoder_enabled = AP::wheelencoder() && (AP::wheelencoder()->num_sensors() > 0);
#endif
_RFRN.ekf_type = ahrs.get_ekf_type();
WRITE_REPLAY_BLOCK_IFCHANGED(RFRN, _RFRN, old);

Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL/AP_HAL_Boards.h
Original file line number Diff line number Diff line change
Expand Up @@ -373,3 +373,7 @@
#endif

#define HAL_GPIO_LED_OFF (!HAL_GPIO_LED_ON)

#ifndef HAL_MAVLINK_ENABLED
#define HAL_MAVLINK_ENABLED 0
#endif
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2482,7 +2482,7 @@ bool AP_InertialSensor::get_primary_accel_cal_sample_avg(uint8_t sample_num, Vec
return true;
}

#if HAL_GCS_ENABLED
#if HAL_GCS_ENABLED || defined(GCS_MAVLINK)
bool AP_InertialSensor::calibrate_gyros()
{
init_gyro();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,7 +289,7 @@ class AP_InertialSensor : AP_AccelCal_Client
void acal_update();
#endif

#if HAL_GCS_ENABLED
#if HAL_GCS_ENABLED || defined(GCS_MAVLINK)
bool calibrate_gyros();

MAV_RESULT calibrate_trim();
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_WheelEncoder/AP_WheelEncoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
*/

#include "AP_WheelEncoder.h"
#if AP_WHEELENCODER_ENABLED
#include "WheelEncoder_Quadrature.h"
#include "WheelEncoder_SITL_Quadrature.h"
#include <AP_Logger/AP_Logger.h>
Expand Down Expand Up @@ -363,3 +364,4 @@ AP_WheelEncoder *wheelencoder()
}

}
#endif // AP_WHEELENCODER_ENABLED
4 changes: 4 additions & 0 deletions libraries/AP_WheelEncoder/AP_WheelEncoder.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@
*/
#pragma once

#include "AP_WheelEncoder_config.h"

#if AP_WHEELENCODER_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
Expand Down Expand Up @@ -133,3 +136,4 @@ class AP_WheelEncoder
namespace AP {
AP_WheelEncoder *wheelencoder();
}
#endif // AP_WHEELENCODER_ENABLED
3 changes: 3 additions & 0 deletions libraries/AP_WheelEncoder/AP_WheelRateControl.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include <AP_WheelEncoder/AP_WheelRateControl.h>
#if AP_WHEELENCODER_ENABLED

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -281,3 +282,5 @@ void AP_WheelRateControl::set_notch_sample_rate(float sample_rate)
_rate_pid1.set_notch_sample_rate(sample_rate);
#endif
}

#endif // AP_WHEELENCODER_ENABLED
5 changes: 5 additions & 0 deletions libraries/AP_WheelEncoder/AP_WheelRateControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@

#pragma once

#include "AP_WheelEncoder_config.h"

#if AP_WHEELENCODER_ENABLED

#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
Expand Down Expand Up @@ -74,3 +78,4 @@ class AP_WheelRateControl {
const AP_WheelEncoder& _wheel_encoder; // pointer to accompanying wheel encoder
uint32_t _last_update_ms; // system time of last call to get_rate_controlled_throttle
};
#endif // AP_WHEELENCODER_ENABLED
5 changes: 4 additions & 1 deletion libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,10 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include <AP_Common/AP_Common.h>
#include "AP_WheelEncoder.h"

#if AP_WHEELENCODER_ENABLED
#include <AP_Common/AP_Common.h>
#include "WheelEncoder_Backend.h"

// base class constructor.
Expand Down Expand Up @@ -56,3 +58,4 @@ void AP_WheelEncoder_Backend::copy_state_to_frontend(int32_t distance_count, uin
_state.error_count = error_count;
_state.last_reading_ms = last_reading_ms;
}
#endif // AP_WHEELENCODER_ENABLED
5 changes: 4 additions & 1 deletion libraries/AP_WheelEncoder/WheelEncoder_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,11 @@
*/
#pragma once

#include <AP_Common/AP_Common.h>
#include "AP_WheelEncoder.h"

#if AP_WHEELENCODER_ENABLED
#include <AP_Common/AP_Common.h>

class AP_WheelEncoder_Backend
{
public:
Expand All @@ -42,3 +44,4 @@ class AP_WheelEncoder_Backend
AP_WheelEncoder &_frontend;
AP_WheelEncoder::WheelEncoder_State &_state;
};
#endif // AP_WHEELENCODER_ENABLED
5 changes: 3 additions & 2 deletions libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include <AP_HAL/AP_HAL.h>

#include "WheelEncoder_Quadrature.h"

#if AP_WHEELENCODER_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;
Expand Down Expand Up @@ -140,3 +140,4 @@ void AP_WheelEncoder_Quadrature::irq_handler(uint8_t pin,
// record update time
irq_state.last_reading_ms = timestamp * 1e-3f;
}
#endif // AP_WHEELENCODER_ENABLED
3 changes: 3 additions & 0 deletions libraries/AP_WheelEncoder/WheelEncoder_Quadrature.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#pragma once

#include "AP_WheelEncoder.h"

#if AP_WHEELENCODER_ENABLED
#include "WheelEncoder_Backend.h"
#include <Filter/Filter.h>
#include <AP_Math/AP_Math.h>
Expand Down Expand Up @@ -57,3 +59,4 @@ class AP_WheelEncoder_Quadrature : public AP_WheelEncoder_Backend
uint8_t last_pin_a_value;
uint8_t last_pin_b_value;
};
#endif // AP_WHEELENCODER_ENABLED
4 changes: 3 additions & 1 deletion libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL

#include "WheelEncoder_SITL_Quadrature.h"
#if AP_WHEELENCODER_ENABLED
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;
Expand Down Expand Up @@ -86,4 +87,5 @@ void AP_WheelEncoder_SITL_Quadrature::update(void)
copy_state_to_frontend(_distance_count, _total_count, 0, time_now);
}

#endif
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
#endif // AP_WHEELENCODER_ENABLED
6 changes: 3 additions & 3 deletions libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@
*/
#pragma once

#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "WheelEncoder_Quadrature.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_WHEELENCODER_ENABLED

#include "WheelEncoder_Backend.h"
#include <AP_Math/AP_Math.h>
#include <SITL/SITL.h>

Expand All @@ -34,4 +34,4 @@ class AP_WheelEncoder_SITL_Quadrature : public AP_WheelEncoder_Backend
uint32_t _total_count; // total number of encoder ticks
};

#endif // CONFIG_HAL_BOARD
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_WHEELENCODER_ENABLED
4 changes: 4 additions & 0 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -1372,6 +1372,10 @@ extern "C" {
#define GCS_SEND_MESSAGE(msg)
#define AP_HAVE_GCS_SEND_TEXT 1

#include "../../../AP_Periph/MAVLink.h"
#define GCS_MAVLINK MAVLink_Periph
#define HAVE_PAYLOAD_SPACE(_chan, id) true

/*
we need a severity enum for the can_printf_severity function with no GCS present
*/
Expand Down

0 comments on commit de1caab

Please sign in to comment.