Skip to content

Commit

Permalink
SITL: add support for simulated GPIO LEDs
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Jul 9, 2024
1 parent 3d0f738 commit 59add49
Show file tree
Hide file tree
Showing 11 changed files with 457 additions and 0 deletions.
10 changes: 10 additions & 0 deletions libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1093,6 +1093,16 @@ void Aircraft::update_external_payload(const struct sitl_input &input)
dronecan->update();
}
#endif

#if AP_SIM_GPIO_LED_2_ENABLED
sim_led2.update(*this);
#endif
#if AP_SIM_GPIO_LED_3_ENABLED
sim_led3.update(*this);
#endif
#if AP_SIM_GPIO_LED_RGB_ENABLED
sim_ledrgb.update(*this);
#endif
}

void Aircraft::add_shove_forces(Vector3f &rot_accel, Vector3f &body_accel)
Expand Down
15 changes: 15 additions & 0 deletions libraries/SITL/SIM_Aircraft.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@
#include <Filter/Filter.h>
#include "SIM_JSON_Master.h"
#include "ServoModel.h"
#include "SIM_GPIO_LED_2.h"
#include "SIM_GPIO_LED_3.h"
#include "SIM_GPIO_LED_RGB.h"

namespace SITL {

Expand Down Expand Up @@ -372,6 +375,18 @@ class Aircraft {
#if AP_TEST_DRONECAN_DRIVERS
DroneCANDevice *dronecan;
#endif


#if AP_SIM_GPIO_LED_2_ENABLED
GPIO_LED_2 sim_led2{13, 14}; // pins to match boards.py
#endif
#if AP_SIM_GPIO_LED_3_ENABLED
GPIO_LED_3 sim_led3{13, 14, 15}; // pins to match boards.py
#endif
#if AP_SIM_GPIO_LED_RGB_ENABLED
GPIO_LED_RGB sim_ledrgb{13, 14, 15}; // pins to match boards.py
#endif

};

} // namespace SITL
Expand Down
32 changes: 32 additions & 0 deletions libraries/SITL/SIM_GPIO_LED_2.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
#include "SIM_config.h"

#if AP_SIM_GPIO_LED_2_ENABLED

#include "SIM_GPIO_LED_2.h"

#include <SITL/SITL.h>

using namespace SITL;

void GPIO_LED_2::init()
{
leds.init();
}

void GPIO_LED_2::update(const class Aircraft &aircraft)
{
if (!init_done) {
init();
init_done = true;
}

const uint16_t pin_mask = AP::sitl()->pin_mask.get();
const bool new_led_states[2] {
((pin_mask & uint16_t((1U<<LED_A_PIN))) != 0),
((pin_mask & uint16_t((1U<<LED_B_PIN))) != 0)
};

leds.set_state(new_led_states);
}

#endif
49 changes: 49 additions & 0 deletions libraries/SITL/SIM_GPIO_LED_2.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
/*
Simulator for GPIO-based "Board LEDs"
./Tools/autotest/sim_vehicle.py -v ArduCopter --gdb --debug --rgbled
reboot
*/


#include "SIM_config.h"

#if AP_SIM_GPIO_LED_2_ENABLED

#include "SIM_LED_n.h"

namespace SITL {

class GPIO_LED_2
{
public:

GPIO_LED_2(uint8_t _LED_A_PIN, uint8_t _LED_B_PIN) :
LED_A_PIN{_LED_A_PIN},
LED_B_PIN{_LED_B_PIN}
{ }

void update(const class Aircraft &aircraft);

private:

void init();
bool init_done;

SIM_LED_n<2>::LEDColour colours[2] {
SIM_LED_n<2>::LEDColour::RED,
SIM_LED_n<2>::LEDColour::BLUE,
};

SIM_LED_n<2> leds{"GPIO_LED_2", colours};

uint8_t LED_A_PIN;
uint8_t LED_B_PIN;
};

} // namespace SITL

#endif // AP_SIM_GPIO_LED_2_ENABLED
33 changes: 33 additions & 0 deletions libraries/SITL/SIM_GPIO_LED_3.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
#include "SIM_config.h"

#if AP_SIM_GPIO_LED_3_ENABLED

#include "SIM_GPIO_LED_3.h"

#include <SITL/SITL.h>

using namespace SITL;

void GPIO_LED_3::init()
{
leds.init();
}

void GPIO_LED_3::update(const class Aircraft &aircraft)
{
if (!init_done) {
init();
init_done = true;
}

const uint16_t pin_mask = AP::sitl()->pin_mask.get();
const bool new_led_states[3] {
((pin_mask & uint16_t((1U<<LED_A_PIN))) != 0),
((pin_mask & uint16_t((1U<<LED_B_PIN))) != 0),
((pin_mask & uint16_t((1U<<LED_C_PIN))) != 0)
};

leds.set_state(new_led_states);
}

#endif
52 changes: 52 additions & 0 deletions libraries/SITL/SIM_GPIO_LED_3.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
/*
Simulator for GPIO-based "Board LEDs"
./Tools/autotest/sim_vehicle.py -v ArduCopter --gdb --debug --rgbled
reboot
*/


#include "SIM_config.h"

#if AP_SIM_GPIO_LED_3_ENABLED

#include "SIM_LED_n.h"

namespace SITL {

class GPIO_LED_3
{
public:

GPIO_LED_3(uint8_t _LED_A_PIN, uint8_t _LED_B_PIN, uint8_t _LED_C_PIN) :
LED_A_PIN{_LED_A_PIN},
LED_B_PIN{_LED_B_PIN},
LED_C_PIN{_LED_C_PIN}
{ }

void update(const class Aircraft &aircraft);

private:

void init();
bool init_done;

SIM_LED_n<3>::LEDColour colours[3] {
SIM_LED_n<3>::LEDColour::RED,
SIM_LED_n<3>::LEDColour::BLUE,
SIM_LED_n<3>::LEDColour::YELLOW,
};

SIM_LED_n<3> leds{"GPIO_LED_3", colours};

uint8_t LED_A_PIN;
uint8_t LED_B_PIN;
uint8_t LED_C_PIN;
};

} // namespace SITL

#endif // AP_SIM_GPIO_LED_3_ENABLED
38 changes: 38 additions & 0 deletions libraries/SITL/SIM_GPIO_LED_RGB.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#include "SIM_config.h"

#if AP_SIM_GPIO_LED_RGB_ENABLED

#include "SIM_GPIO_LED_RGB.h"

#include <SITL/SITL.h>

using namespace SITL;

void GPIO_LED_RGB::init()
{
leds.init();
rgbled.init();
}

void GPIO_LED_RGB::update(const class Aircraft &aircraft)
{
if (!init_done) {
init();
init_done = true;
}

const uint16_t pin_mask = AP::sitl()->pin_mask.get();

const bool red = ((pin_mask & uint16_t((1U<<LED_RED_PIN))) != 0);
const bool green = ((pin_mask & uint16_t((1U<<LED_GREEN_PIN))) != 0);
const bool blue = ((pin_mask & uint16_t((1U<<LED_BLUE_PIN))) != 0);

const bool new_led_states[3] { red, green, blue };
leds.set_state(new_led_states);

// FIXME: check why we need to "!" here; do we need to move
// ON_VALUE into here?
rgbled.set_colours((!red)*255, (!green)*255, (!blue)*255);
}

#endif
54 changes: 54 additions & 0 deletions libraries/SITL/SIM_GPIO_LED_RGB.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
/*
Simulator for GPIO-based "Board LEDs"
./Tools/autotest/sim_vehicle.py -v ArduCopter --gdb --debug --rgbled
reboot
*/


#include "SIM_config.h"

#if AP_SIM_GPIO_LED_RGB_ENABLED

#include "SIM_LED_n.h"
#include "SIM_RGBLED.h"

namespace SITL {

class GPIO_LED_RGB
{
public:

GPIO_LED_RGB(uint8_t _LED_RED_PIN, uint8_t _LED_GREEN_PIN, uint8_t _LED_BLUE_PIN) :
LED_RED_PIN{_LED_RED_PIN},
LED_GREEN_PIN{_LED_GREEN_PIN},
LED_BLUE_PIN{_LED_BLUE_PIN}
{ }

void update(const class Aircraft &aircraft);

private:

void init();
bool init_done;

SIM_LED_n<3>::LEDColour colours[3] {
SIM_LED_n<3>::LEDColour::RED,
SIM_LED_n<3>::LEDColour::GREEN,
SIM_LED_n<3>::LEDColour::BLUE,
};

SIM_LED_n<3> leds{"GPIO_LED_RGB", colours};
SIM_RGBLED rgbled{"GPIO_LED_RGB2"};

uint8_t LED_RED_PIN;
uint8_t LED_GREEN_PIN;
uint8_t LED_BLUE_PIN;
};

} // namespace SITL

#endif // AP_SIM_GPIO_LED_RGB_ENABLED
Loading

0 comments on commit 59add49

Please sign in to comment.