AP_PiccoloCAN: Add user configurable operations to adjust Piccolo CAN ESC behaviour
This commit is contained in:
parent
c78dcb15a1
commit
a98babc02c
@ -54,6 +54,12 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = {
|
||||
AP_SUBGROUPPTR(_testcan, "TST_", 4, AP_CANManager::CANDriver_Params, CANTester),
|
||||
#endif
|
||||
|
||||
#if (APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub))
|
||||
// @Group: PC_
|
||||
// @Path: ../AP_PiccoloCAN/AP_PiccoloCAN.cpp
|
||||
AP_SUBGROUPPTR(_pcan, "PC_", 5, AP_BoardConfig_CAN::Driver, AP_PiccoloCAN),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
#endif
|
||||
|
@ -23,6 +23,7 @@
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
@ -37,13 +38,48 @@
|
||||
#include <AP_PiccoloCAN/piccolo_protocol/ESCVelocityProtocol.h>
|
||||
#include <AP_PiccoloCAN/piccolo_protocol/ESCPackets.h>
|
||||
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define debug_can(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "PiccoloCAN", fmt, ##args); } while (0)
|
||||
|
||||
// table of user-configurable Piccolo CAN bus parameters
|
||||
const AP_Param::GroupInfo AP_PiccoloCAN::var_info[] = {
|
||||
|
||||
// @Param: ESC_BM
|
||||
// @DisplayName: ESC channels
|
||||
// @Description: Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN
|
||||
// @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ESC_BM", 1, AP_PiccoloCAN, _esc_bm, 0),
|
||||
|
||||
// @Param: ESC_MS
|
||||
// @DisplayName: ESC command rate
|
||||
// @Description: Output rate of ESC command messages
|
||||
// @Units: ms
|
||||
// @Range: 2 100
|
||||
AP_GROUPINFO("ESC_MS", 2, AP_PiccoloCAN, _esc_ms, PICCOLO_MSG_RATE_MS_DEFAULT),
|
||||
|
||||
// @Param: SRV_BM
|
||||
// @DisplayName: Servo channels
|
||||
// @Description: Bitmask defining which servo channels are to be transmitted over PiccoloCAN
|
||||
// @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15, 15: Servo 16
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SRV_BM", 3, AP_PiccoloCAN, _srv_bm, 0),
|
||||
|
||||
// @Param: SRV_MS
|
||||
// @DisplayName: Servo command rate
|
||||
// @Description: Output rate of servo command messages
|
||||
// @Units: ms
|
||||
// @Range: 2 100
|
||||
AP_GROUPINFO("SRV_MS", 4, AP_PiccoloCAN, _srv_ms, PICCOLO_MSG_RATE_MS_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
AP_PiccoloCAN::AP_PiccoloCAN()
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
debug_can(AP_CANManager::LOG_INFO, "PiccoloCAN: constructed\n\r");
|
||||
}
|
||||
|
||||
|
@ -21,6 +21,8 @@
|
||||
#include <AP_CANManager/AP_CANDriver.h>
|
||||
#include <AP_HAL/Semaphores.h>
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
#include "piccolo_protocol/ESCPackets.h"
|
||||
|
||||
// maximum number of ESC allowed on CAN bus simultaneously
|
||||
@ -33,6 +35,10 @@
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
#define PICCOLO_MSG_RATE_MS_MIN 2
|
||||
#define PICCOLO_MSG_RATE_MS_MAX 100
|
||||
#define PICCOLO_MSG_RATE_MS_DEFAULT 20
|
||||
|
||||
class AP_PiccoloCAN : public AP_CANDriver
|
||||
{
|
||||
public:
|
||||
@ -60,6 +66,8 @@ public:
|
||||
AP_PiccoloCAN(const AP_PiccoloCAN &other) = delete;
|
||||
AP_PiccoloCAN &operator=(const AP_PiccoloCAN&) = delete;
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// Return PiccoloCAN from @driver_index or nullptr if it's not ready or doesn't exist
|
||||
static AP_PiccoloCAN *get_pcan(uint8_t driver_index);
|
||||
|
||||
@ -125,6 +133,13 @@ private:
|
||||
|
||||
} _esc_info[PICCOLO_CAN_MAX_NUM_ESC];
|
||||
|
||||
// Piccolo CAN parameters
|
||||
AP_Int32 _srv_bm; //! Servo selection bitmask
|
||||
AP_Int32 _srv_ms; //! Servo update rate (ms)
|
||||
|
||||
AP_Int32 _esc_bm; //! ESC selection bitmask
|
||||
AP_Int32 _esc_ms; //! ESC update rate (ms)
|
||||
|
||||
};
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
||||
|
Loading…
Reference in New Issue
Block a user