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

changed buttons publish to rise and fall #16

Merged
merged 1 commit into from
Jun 23, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion include/main.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ std::map<double, uint8_t> servo_voltage_configuration{
#define MOTOR_FL MOTOR4
#define MOTOR_RR MOTOR2
#define MOTOR_RL MOTOR3
time_t last_button_press_time[BUTTONS_COUNT];

constexpr uint8_t POLARITY = 0b00111100;
constexpr float ROBOT_LENGTH = 0.197;
Expand Down
29 changes: 17 additions & 12 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,22 @@ std_msgs__msg__Bool button_msgs[BUTTONS_COUNT];

static uint32_t spin_count = 1;

static void button1Callback() {
static void button1FallCallback() {
buttons_publish_flag[0] = true;
}

static void button2Callback() {
static void button2FallCallback() {
buttons_publish_flag[1] = true;
}

static void button1RiseCallback() {
buttons_publish_flag[0] = false;
}

static void button2RiseCallback() {
buttons_publish_flag[1] = false;
}

void range_sensors_msg_handler() {
osEvent evt1 = distance_sensor_mail_box.get(0);
if (evt1.status == osEventMail) {
Expand Down Expand Up @@ -112,14 +120,8 @@ void battery_msg_handler() {

void button_msgs_handler() {
for(auto i = 0u; i < BUTTONS_COUNT; ++i){
if (buttons_publish_flag[i]) {
button_msgs[i].data = true;
buttons_publish_flag[i] = false;
publish_button_msg(&button_msgs[i], i);
last_button_press_time[i] = time(NULL);
}
else if(time(NULL) - last_button_press_time[i] > button_release_time){
button_msgs[i].data = false;
if (buttons_publish_flag[i] != button_msgs[i].data) {
button_msgs[i].data = buttons_publish_flag[i];
publish_button_msg(&button_msgs[i], i);
}
}
Expand Down Expand Up @@ -309,8 +311,11 @@ int main() {

button1.mode(PullUp);
button2.mode(PullUp);
button1.fall(button1Callback);
button2.fall(button2Callback);
button1.fall(button1FallCallback);
button2.fall(button2FallCallback);
button1.rise(button1RiseCallback);
button2.rise(button2RiseCallback);


bool distance_sensors_init_flag = false;
bool imu_init_flag = false;
Expand Down
3 changes: 2 additions & 1 deletion src/microros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ bool microros_init() {
rcl_allocator = rcl_get_default_allocator();
RCCHECK(rclc_support_init(&support, 0, NULL, &rcl_allocator));
RCCHECK(rclc_node_init_default(&node, NODE_NAME, "", &support));

if (not init_wheels_command_subscriber() or
not init_servos_command_subscriber() or
not init_wheels_state_publisher() or
Expand Down Expand Up @@ -151,7 +152,7 @@ bool init_range_publishers() {

bool init_button_publishers() {
for (auto i = 0u; i < BUTTONS_COUNT; ++i) {
RCCHECK(rclc_publisher_init_best_effort(
RCCHECK(rclc_publisher_init_default(
&buttons_pubs[i],
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool),
Expand Down