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

Feature/dynamic reconfigure #12

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion time_stamper_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ project(time_stamper_ros)
add_compile_options(-std=c++17 -Wdeprecated-declarations)

find_package(catkin_simple REQUIRED)
catkin_simple()
catkin_simple(ALL_DEPS_REQUIRED)


Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

unecessary vspace

cs_add_library(${PROJECT_NAME}
Expand Down
14 changes: 14 additions & 0 deletions time_stamper_ros/cfg/Led.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
#!/usr/bin/env python
PACKAGE = "time_stamper_ros"

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()
gen.add("frequency", int_t, 0, "Clock frequency", 50, 1, 10526315)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

hmm I wonder if it makes sense to change frequency completely freely as an integer, as usually not all frequencies can be achieved by the clock. Maybe a divisor makes more sense? Depends on the use case, though.
Make sure the default, min and max are correct.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hm, this is difficult problem indeed. A divider may also be hard to work with for some scrip not knowing very well about the hardware. One possible way to deal with this is on the node side to change the requested value to a closest possible frequency (see my comment below for how to do that). For interactive configuration this should work well. The user would effectively only be able to adjust the value to something possible. And scripts may also be happy with that. If they really need to know precisely, they could read the effective value back and work with that.


size_enum = gen.enum([gen.const("Fps", int_t, 0, "Fps Mode"),
gen.const("Exposure", int_t, 1, "Exposure Mode")],
"Set Led Mode")

gen.add("mode", int_t, 0, "Led Mode", 1, 0, 3, edit_method=size_enum)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

3 as max value probably makes no sense given that there are only 2 values possible

exit(gen.generate(PACKAGE, "time_stamper_ros", "Led"))
16 changes: 14 additions & 2 deletions time_stamper_ros/include/Node.h
Original file line number Diff line number Diff line change
@@ -1,13 +1,17 @@
#pragma once
#include <iostream>
#include <string>

#include <ros/ros.h>
#include <dynamic_reconfigure/server.h>

#include "sysfs/SysfsGpio.h"
#include "sysfs/SysfsPwm.h"
#include "time_stamper_ros/LedConfig.h"

enum LedMode {
FPS,
EXPOSURE
FPS = 0,
EXPOSURE = 1
};
Comment on lines 12 to 15
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.


class Node {
Expand Down Expand Up @@ -37,6 +41,12 @@ class Node {
*/
void cleanUp();

/**
* Dynamic reconfigure callback
* @param config
*/
void configCallback(time_stamper_ros::LedConfig &config);

/**
* Default destructor.
*/
Expand All @@ -49,11 +59,13 @@ class Node {
static bool run_node;
private:
bool setGpioMode();
bool is_initialized_{false};

LedMode mode_;
ros::Publisher timestamp_pub_;
ros::NodeHandle nh_;
IPwmSubsystem &pwm_subsystem_;
IGpioSubsystem &gpio_subsystem_;
dynamic_reconfigure::Server<time_stamper_ros::LedConfig> server_;
};

1 change: 1 addition & 0 deletions time_stamper_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,5 @@
<depend>std_msgs</depend>
<depend>message_generation</depend>
<depend>message_runtime</depend>
<depend>dynamic_reconfigure</depend>
</package>
21 changes: 19 additions & 2 deletions time_stamper_ros/src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,13 @@
#include "time_stamper_ros/Timestamp.h"
#include "TimestampManager.h"


bool Node::run_node = true;

Node::Node(IPwmSubsystem &pwm_subsystem, IGpioSubsystem &gpio_subsystem, LedMode led_mode)
: pwm_subsystem_(pwm_subsystem), gpio_subsystem_(gpio_subsystem), mode_(led_mode) {}
: pwm_subsystem_(pwm_subsystem), gpio_subsystem_(gpio_subsystem), mode_(led_mode) {
server_.setCallback(boost::bind(&Node::configCallback, this, _1));
}

bool Node::init(int frequency, bool forceReset) {
if (!setGpioMode()) {
Expand Down Expand Up @@ -47,6 +50,7 @@ bool Node::init(int frequency, bool forceReset) {
}
ROS_INFO("Started pwm");
}
is_initialized_ = true;
return true;
}

Expand Down Expand Up @@ -85,7 +89,7 @@ bool Node::setGpioMode() {
}
ROS_INFO("Exported GPIO");
} else {
ROS_INFO("GPIO already exported");
ROS_INFO_ONCE("GPIO already exported");
}

GPIO_MODE gpio_mode;
Expand All @@ -106,3 +110,16 @@ bool Node::setGpioMode() {
}
return true;
}

void Node::configCallback(time_stamper_ros::LedConfig &config) {

//Ignore if not initialized to avoid memory corruption
if (!is_initialized_) {
return;
}
mode_ = static_cast<LedMode>(config.mode); //Convert int to enum

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Around here you could mutate the config object and set the frequency to a closest valid value.

pwm_subsystem_.setFrequency(config.frequency);
setGpioMode();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

hmm I guess this sets the LedMode to the GPIO driver?
Nitpick, but for maintainability it would be better to have a comment and/or put this next to the mode_ assignment. So future Mariano or Hannes don't need to think too much about sideeffects when changing anything here.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, this isn't perfect this way. Without looking much into the code (lack of time :( ), to me the underlying problem seems to be again, the fact that this method doesn't take the mode (static_cast<LedMode>(config.mode)) as an argument. Wouldn't that make more sense? Then, here you wouldn't need to use the knowledge how the mode is stored (mode_). Maybe you wouldn't even need the mode_ variable if you could just directly pass it to the hardware. Generally, I'd recommend to try avoiding redundant state (and that includes hardware state in addition to memory state). Duplicating it may of course be justified by the hardware being to slow or not able to provide back the value in case it needed again somewhere later.

ROS_INFO_STREAM("Config update received. Mode: " << mode_ << " Frequency: " << config.frequency);
}