AP_Scripting: don't include CAN support on periph if there is only one CAN port
This commit is contained in:
parent
75ac3f98fa
commit
fc68bf8979
@ -84,7 +84,7 @@ public:
|
|||||||
uint8_t num_i2c_devices;
|
uint8_t num_i2c_devices;
|
||||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> *_i2c_dev[SCRIPTING_MAX_NUM_I2C_DEVICE];
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> *_i2c_dev[SCRIPTING_MAX_NUM_I2C_DEVICE];
|
||||||
|
|
||||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
#if AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
// Scripting CAN sensor
|
// Scripting CAN sensor
|
||||||
ScriptingCANSensor *_CAN_dev;
|
ScriptingCANSensor *_CAN_dev;
|
||||||
ScriptingCANSensor *_CAN_dev2;
|
ScriptingCANSensor *_CAN_dev2;
|
||||||
|
@ -17,7 +17,7 @@
|
|||||||
*/
|
*/
|
||||||
#include "AP_Scripting_CANSensor.h"
|
#include "AP_Scripting_CANSensor.h"
|
||||||
|
|
||||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
#if AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
|
|
||||||
// handler for outgoing frames, using uint32
|
// handler for outgoing frames, using uint32
|
||||||
bool ScriptingCANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
|
bool ScriptingCANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
|
||||||
@ -79,4 +79,4 @@ void ScriptingCANBuffer::add_buffer(ScriptingCANBuffer* new_buff) {
|
|||||||
next->add_buffer(new_buff);
|
next->add_buffer(new_buff);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
|
#endif // AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
|
@ -18,9 +18,19 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#if defined(HAL_BUILD_AP_PERIPH)
|
||||||
|
// Must have at least two CAN ports on Periph
|
||||||
|
#define AP_SCRIPTING_CAN_SENSOR_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS > 1)
|
||||||
|
#else
|
||||||
|
#define AP_SCRIPTING_CAN_SENSOR_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
|
|
||||||
#include <AP_CANManager/AP_CANSensor.h>
|
#include <AP_CANManager/AP_CANSensor.h>
|
||||||
|
|
||||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
|
||||||
class ScriptingCANBuffer;
|
class ScriptingCANBuffer;
|
||||||
class ScriptingCANSensor : public CANSensor {
|
class ScriptingCANSensor : public CANSensor {
|
||||||
public:
|
public:
|
||||||
@ -76,4 +86,4 @@ private:
|
|||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
|
#endif // AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
|
@ -549,12 +549,12 @@ singleton AP_InertialSensor method get_accel_health boolean uint8_t'skip_check
|
|||||||
|
|
||||||
singleton CAN manual get_device lua_get_CAN_device 1
|
singleton CAN manual get_device lua_get_CAN_device 1
|
||||||
singleton CAN manual get_device2 lua_get_CAN_device2 1
|
singleton CAN manual get_device2 lua_get_CAN_device2 1
|
||||||
singleton CAN depends HAL_MAX_CAN_PROTOCOL_DRIVERS
|
singleton CAN depends AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
|
|
||||||
include AP_Scripting/AP_Scripting_CANSensor.h depends HAL_MAX_CAN_PROTOCOL_DRIVERS
|
include AP_Scripting/AP_Scripting_CANSensor.h
|
||||||
include AP_HAL/AP_HAL.h
|
include AP_HAL/AP_HAL.h
|
||||||
|
|
||||||
userdata AP_HAL::CANFrame depends HAL_MAX_CAN_PROTOCOL_DRIVERS
|
userdata AP_HAL::CANFrame depends AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
userdata AP_HAL::CANFrame rename CANFrame
|
userdata AP_HAL::CANFrame rename CANFrame
|
||||||
userdata AP_HAL::CANFrame field id uint32_t'skip_check read write
|
userdata AP_HAL::CANFrame field id uint32_t'skip_check read write
|
||||||
userdata AP_HAL::CANFrame field data'array int(ARRAY_SIZE(ud->data)) uint8_t'skip_check read write
|
userdata AP_HAL::CANFrame field data'array int(ARRAY_SIZE(ud->data)) uint8_t'skip_check read write
|
||||||
@ -564,7 +564,7 @@ userdata AP_HAL::CANFrame method isExtended boolean
|
|||||||
userdata AP_HAL::CANFrame method isRemoteTransmissionRequest boolean
|
userdata AP_HAL::CANFrame method isRemoteTransmissionRequest boolean
|
||||||
userdata AP_HAL::CANFrame method isErrorFrame boolean
|
userdata AP_HAL::CANFrame method isErrorFrame boolean
|
||||||
|
|
||||||
ap_object ScriptingCANBuffer depends HAL_MAX_CAN_PROTOCOL_DRIVERS
|
ap_object ScriptingCANBuffer depends AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
ap_object ScriptingCANBuffer method write_frame boolean AP_HAL::CANFrame uint32_t'skip_check
|
ap_object ScriptingCANBuffer method write_frame boolean AP_HAL::CANFrame uint32_t'skip_check
|
||||||
ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null
|
ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null
|
||||||
|
|
||||||
|
@ -630,7 +630,7 @@ int AP_HAL__I2CDevice_read_registers(lua_State *L) {
|
|||||||
return success;
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
#if AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
int lua_get_CAN_device(lua_State *L) {
|
int lua_get_CAN_device(lua_State *L) {
|
||||||
|
|
||||||
// Allow : and . access
|
// Allow : and . access
|
||||||
@ -680,7 +680,7 @@ int lua_get_CAN_device2(lua_State *L) {
|
|||||||
|
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
|
#endif // AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||||
|
|
||||||
/*
|
/*
|
||||||
directory listing, return table of files in a directory
|
directory listing, return table of files in a directory
|
||||||
|
Loading…
Reference in New Issue
Block a user