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

SITL: support both multicast and socketcan in CAN SITL #24779

Merged
merged 12 commits into from
Aug 29, 2023
8 changes: 0 additions & 8 deletions .github/workflows/test_coverage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -56,14 +56,6 @@ jobs:
- name: setup ccache
run: |
. .github/workflows/ccache.env
- name: Configure CAN
if: ${{ matrix.config == 'sitltest-can'}}
run: |
sudo apt-get update
sudo apt-get -y install can-utils iproute2 linux-modules-extra-$(uname -r)
sudo modprobe vcan
sudo ip link add dev vcan0 type vcan
sudo ip link set up vcan0
- name: test ${{matrix.config}} ${{ matrix.toolchain }}
env:
CI_BUILD_TARGET: ${{matrix.config}}
Expand Down
9 changes: 0 additions & 9 deletions .github/workflows/test_sitl_periph.yml
Original file line number Diff line number Diff line change
Expand Up @@ -230,15 +230,6 @@ jobs:
- name: setup ccache
run: |
. .github/workflows/ccache.env
- name: setup can-utils
run: |
kernel_ver=`uname -r`
if [ "$kernel_ver" = "5.4.0-1032-azure" ] || [ "$kernel_ver" = "5.11.4-051104-generic" ]; then echo "Unsupported Kernel $kernel_ver" && exit 0; fi;
sudo apt-get update
sudo apt-get -y install can-utils iproute2 linux-modules-extra-$(uname -r)
sudo modprobe vcan
sudo ip link add dev vcan0 type vcan
sudo ip link set up vcan0
- name: test ${{matrix.config}}
env:
CI_BUILD_TARGET: ${{matrix.config}}
Expand Down
3 changes: 2 additions & 1 deletion Tools/AP_Periph/rc_out.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,8 @@ void AP_Periph_FW::rcout_update()
const bool has_esc_rawcommand_timed_out = esc_timeout_ms != 0 && ((now_ms - last_esc_raw_command_ms) >= esc_timeout_ms);
if (last_esc_num_channels > 0 && has_esc_rawcommand_timed_out) {
// If we've seen ESCs previously, and a timeout has occurred, then zero the outputs
int16_t esc_output[last_esc_num_channels] {};
int16_t esc_output[last_esc_num_channels];
memset(esc_output, 0, sizeof(esc_output));
rcout_esc(esc_output, last_esc_num_channels);

// register that the output has been changed
Expand Down
17 changes: 11 additions & 6 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -626,10 +626,7 @@ def get_board(ctx):
class sitl(Board):

def __init__(self):
if Utils.unversioned_sys_platform().startswith("linux"):
self.with_can = True
else:
self.with_can = False
self.with_can = True

def configure_env(self, cfg, env):
super(sitl, self).configure_env(cfg, env)
Expand All @@ -654,8 +651,16 @@ def configure_env(self, cfg, env):
cfg.define('HAL_NUM_CAN_IFACES', 2)
env.DEFINES.update(CANARD_MULTI_IFACE=1,
CANARD_IFACE_ALL = 0x3,
CANARD_ENABLE_CANFD = 1,
CANARD_ENABLE_ASSERTS = 1)
CANARD_ENABLE_CANFD = 1,
CANARD_ENABLE_ASSERTS = 1)
if not cfg.options.force_32bit:
# needed for cygwin
env.CXXFLAGS += [ '-DCANARD_64_BIT=1' ]
env.CFLAGS += [ '-DCANARD_64_BIT=1' ]
if Utils.unversioned_sys_platform().startswith("linux"):
cfg.define('HAL_CAN_WITH_SOCKETCAN', 1)
else:
cfg.define('HAL_CAN_WITH_SOCKETCAN', 0)

env.CXXFLAGS += [
'-Werror=float-equal',
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/sim_vehicle.py
Original file line number Diff line number Diff line change
Expand Up @@ -1148,7 +1148,7 @@ def generate_frame_help():
group_sim.add_option("", "--can-peripherals",
action='store_true',
default=False,
help="start a DroneCAN peripheral instance (use Tools/scripts/CAN/can_sitl_nodev.sh first)")
help="start a DroneCAN peripheral instance")
group_sim.add_option("-A", "--sitl-instance-args",
type='string',
default=None,
Expand Down
10 changes: 6 additions & 4 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1215,22 +1215,24 @@ bool AP_AHRS::_get_secondary_position(Location &loc) const
// EKF has a better ground speed vector estimate
Vector2f AP_AHRS::_groundspeed_vector(void)
{
Vector3f vec;

switch (active_EKF_type()) {
case EKFType::NONE:
break;

#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
case EKFType::TWO: {
Vector3f vec;
EKF2.getVelNED(vec);
return vec.xy();
}
#endif

#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
case EKFType::THREE: {
Vector3f vec;
EKF3.getVelNED(vec);
return vec.xy();
}
#endif

#if AP_AHRS_SIM_ENABLED
Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,7 @@ const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = {

/// Constructor
AP_BattMonitor_DroneCAN::AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_DroneCAN_Type type, AP_BattMonitor_Params &params) :
AP_BattMonitor_Backend(mon, mon_state, params),
_type(type)
AP_BattMonitor_Backend(mon, mon_state, params)
{
AP_Param::setup_object_defaults(this,var_info);
_state.var_info = var_info;
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,6 @@ class AP_BattMonitor_DroneCAN : public AP_BattMonitor_Backend
bool use_CAN_SoC() const;

AP_BattMonitor::BattMonitor_State _interim_state;
BattMonitor_DroneCAN_Type _type;

HAL_Semaphore _sem_battmon;

Expand Down
1 change: 0 additions & 1 deletion libraries/AP_CANManager/AP_CANManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,6 @@ class AP_CANManager

private:
AP_Int8 _driver_type;
AP_CANDriver* _testcan;
AP_CANDriver* _uavcan;
AP_CANDriver* _piccolocan;
};
Expand Down
9 changes: 3 additions & 6 deletions libraries/AP_Compass/AP_Compass_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,8 @@ extern const AP_HAL::HAL& hal;
AP_Compass_DroneCAN::DetectedModules AP_Compass_DroneCAN::_detected_modules[];
HAL_Semaphore AP_Compass_DroneCAN::_sem_registry;

AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid)
: _ap_dronecan(ap_dronecan)
, _node_id(node_id)
, _sensor_id(sensor_id)
, _devid(devid)
AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid) :
_devid(devid)
{
}

Expand All @@ -59,7 +56,7 @@ AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index)
if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) {
WITH_SEMAPHORE(_sem_registry);
// Register new Compass mode to a backend
driver = new AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid);
driver = new AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid);
if (driver) {
if (!driver->init()) {
delete driver;
Expand Down
5 changes: 1 addition & 4 deletions libraries/AP_Compass/AP_Compass_DroneCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

class AP_Compass_DroneCAN : public AP_Compass_Backend {
public:
AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid);
AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid);

void read(void) override;

Expand All @@ -30,9 +30,6 @@ class AP_Compass_DroneCAN : public AP_Compass_Backend {

uint8_t _instance;

AP_DroneCAN* _ap_dronecan;
uint8_t _node_id;
uint8_t _sensor_id;
uint32_t _devid;

// Module Detection Registry
Expand Down
16 changes: 8 additions & 8 deletions libraries/AP_GPS/AP_GPS_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,7 @@ AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan,
*/
void AP_GPS_DroneCAN::handle_velocity(const float vx, const float vy, const float vz)
{
if (!isnanf(vx)) {
if (!isnan(vx)) {
const Vector3f vel(vx, vy, vz);
interim_state.velocity = vel;
velocity_to_speed_course(interim_state);
Expand Down Expand Up @@ -391,21 +391,21 @@ void AP_GPS_DroneCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uin
handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]);

if (msg.covariance.len == 6) {
if (!isnanf(msg.covariance.data[0])) {
if (!isnan(msg.covariance.data[0])) {
interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]);
interim_state.have_horizontal_accuracy = true;
} else {
interim_state.have_horizontal_accuracy = false;
}
if (!isnanf(msg.covariance.data[2])) {
if (!isnan(msg.covariance.data[2])) {
interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]);
interim_state.have_vertical_accuracy = true;
} else {
interim_state.have_vertical_accuracy = false;
}
if (!isnanf(msg.covariance.data[3]) &&
!isnanf(msg.covariance.data[4]) &&
!isnanf(msg.covariance.data[5])) {
if (!isnan(msg.covariance.data[3]) &&
!isnan(msg.covariance.data[4]) &&
!isnan(msg.covariance.data[5])) {
interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3);
interim_state.have_speed_accuracy = true;
} else {
Expand Down Expand Up @@ -479,12 +479,12 @@ void AP_GPS_DroneCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg)
{
WITH_SEMAPHORE(sem);

if (!isnanf(msg.hdop)) {
if (!isnan(msg.hdop)) {
seen_aux = true;
interim_state.hdop = msg.hdop * 100.0;
}

if (!isnanf(msg.vdop)) {
if (!isnan(msg.vdop)) {
seen_aux = true;
interim_state.vdop = msg.vdop * 100.0;
}
Expand Down
Loading
Loading