Skip to content

Commit 2a1f61e

Browse files
committed
Imported upstream version '1.6.0' of 'upstream'
1 parent f22f1f4 commit 2a1f61e

15 files changed

+334
-37
lines changed

.github/workflows/ci.yml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
11
name: Build
22

3-
on: push
3+
on: [push, pull_request]
44

55
jobs:
66
build:
77
runs-on: ubuntu-22.04
8-
container: ros:iron
8+
container: ros:jazzy
99
steps:
1010
- name: Check out repository code
1111
uses: actions/checkout@v3

CHANGELOG.rst

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,14 @@
22
Changelog for package rig_reconfigure
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
1.6.0 (2025-05-03)
6+
------------------
7+
* fix wrong bounds on one-sided numeric parameter bounds (`#46 <https://github.com/teamspatzenhirn/rig_reconfigure/pull/46>`_)
8+
* fix errors when exiting rig via sigint (`#45 <https://github.com/teamspatzenhirn/rig_reconfigure/pull/45>`_)
9+
* Add support for parameter ranges and disabling readonly parameters. (`#42 <https://github.com/teamspatzenhirn/rig_reconfigure/pull/42>`)
10+
* Fix parameter input widget widths (`#41 <https://github.com/teamspatzenhirn/rig_reconfigure/pull/41>`_)
11+
* Contributors: Dominik, Jonas Otto, Marc Alban
12+
513
1.5.0 (2024-07-20)
614
------------------
715
* create config directory if it doesnt exist (`#40 <https://github.com/teamspatzenhirn/rig_reconfigure/issues/40>`_)

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ set(CMAKE_CXX_STANDARD 20)
66
# find dependencies
77
find_package(ament_cmake REQUIRED)
88
find_package(rclcpp REQUIRED)
9+
find_package(backward_ros QUIET)
910

1011
# Download imgui
1112
include(FetchContent)

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ The following features are not implemented yet, but would be nice to have. PRs a
3030
- feedback about the success of modifying parameters
3131
(intended: directly behind the parameters, e.g. using spinners / checkmarks)
3232
- support for array parameters
33-
- consideration of limits specified in the [parameter description](https://docs.ros2.org/galactic/api/rcl_interfaces/msg/ParameterDescriptor.html)
33+
- support for one-sided value bounds specified in the [parameter description](https://docs.ros2.org/galactic/api/rcl_interfaces/msg/ParameterDescriptor.html)
3434

3535
## Known Issues
3636

include/parameter_tree.hpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,9 @@
1212
#include <memory>
1313
#include <optional>
1414
#include <utility>
15+
16+
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
17+
1518
#include "responses.hpp"
1619

1720
/**
@@ -22,16 +25,19 @@ struct TreeElement {
2225
TreeElement(const ROSParameter &parameter_, std::string fullParameterPath_,
2326
std::optional<std::size_t> patternStart_ = std::nullopt,
2427
std::optional<std::size_t> patternEnd_ = std::nullopt) :
25-
name(parameter_.name), fullPath(std::move(fullParameterPath_)), value(parameter_.value),
28+
name(parameter_.name), description(parameter_.description),
29+
fullPath(std::move(fullParameterPath_)), value(parameter_.value),
2630
searchPatternStart(patternStart_), searchPatternEnd(patternEnd_) {};
2731

28-
TreeElement(std::string name_, std::string fullParameterPath_, ROSParameterVariant value_,
32+
TreeElement(std::string name_, const rcl_interfaces::msg::ParameterDescriptor &description_,
33+
std::string fullParameterPath_, ROSParameterVariant value_,
2934
std::optional<std::size_t> patternStart_ = std::nullopt,
3035
std::optional<std::size_t> patternEnd_ = std::nullopt) :
31-
name(std::move(name_)), fullPath(std::move(fullParameterPath_)), value(std::move(value_)),
32-
searchPatternStart(patternStart_), searchPatternEnd(patternEnd_) {};
36+
name(std::move(name_)), description(description_), fullPath(std::move(fullParameterPath_)),
37+
value(std::move(value_)), searchPatternStart(patternStart_), searchPatternEnd(patternEnd_) {};
3338

3439
std::string name; // parameter name without prefixes
40+
rcl_interfaces::msg::ParameterDescriptor description;
3541

3642
// in addition to the name we store the full path of the parameter in the leaf nodes of the tree in order to be
3743
// able to support the mixing of different separators

include/requests.hpp

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,15 @@
1212
#include <utility>
1313
#include <vector>
1414
#include <string>
15+
16+
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
17+
1518
#include "ros_parameter.hpp"
1619

1720
struct Request {
1821
enum class Type {
19-
TERMINATE, QUERY_NODE_NAMES, QUERY_NODE_PARAMETERS, QUERY_PARAMETER_VALUES, MODIFY_PARAMETER_VALUE
22+
TERMINATE, QUERY_NODE_NAMES, QUERY_NODE_PARAMETERS, QUERY_PARAMETER_DESCRIPTIONS,
23+
QUERY_PARAMETER_VALUES, MODIFY_PARAMETER_VALUE
2024
};
2125

2226
explicit Request(Type type_) : type(type_) {};
@@ -28,7 +32,18 @@ struct Request {
2832
using RequestPtr = std::shared_ptr<Request>;
2933

3034
struct ParameterValueRequest : Request {
31-
explicit ParameterValueRequest(const std::vector<std::string> &parameterNames_) : Request(Type::QUERY_PARAMETER_VALUES), parameterNames(parameterNames_) {};
35+
explicit ParameterValueRequest(
36+
const std::vector<std::string> &parameterNames_,
37+
const std::vector<rcl_interfaces::msg::ParameterDescriptor> &parameterDescriptors_)
38+
: Request(Type::QUERY_PARAMETER_VALUES), parameterNames(parameterNames_),
39+
parameterDescriptors(parameterDescriptors_) {};
40+
41+
std::vector<std::string> parameterNames;
42+
std::vector<rcl_interfaces::msg::ParameterDescriptor> parameterDescriptors;
43+
};
44+
45+
struct ParameterDescriptionRequest : Request {
46+
explicit ParameterDescriptionRequest(const std::vector<std::string> &parameterNames_) : Request(Type::QUERY_PARAMETER_DESCRIPTIONS), parameterNames(parameterNames_) {};
3247

3348
std::vector<std::string> parameterNames;
3449
};

include/ros_parameter.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,20 @@
1212
#include <string>
1313
#include <variant>
1414

15+
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
16+
1517
// TODO: add arrays
1618
using ROSParameterVariant = std::variant<bool, int, double, std::string>;
1719

1820
struct ROSParameter {
1921
ROSParameter(std::string name_, ROSParameterVariant value_) :
2022
name(std::move(name_)), value(std::move(value_)) {};
2123

24+
ROSParameter(rcl_interfaces::msg::ParameterDescriptor description_, ROSParameterVariant value_) :
25+
description(std::move(description_)), name(description.name), value(std::move(value_)) {};
26+
27+
28+
rcl_interfaces::msg::ParameterDescriptor description;
2229
std::string name;
2330
ROSParameterVariant value;
2431
};

include/service_wrapper.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,14 +78,17 @@ class ServiceWrapper {
7878

7979
// clients for calling the different services
8080
rclcpp::Client<rcl_interfaces::srv::ListParameters>::SharedPtr listParametersClient;
81+
rclcpp::Client<rcl_interfaces::srv::DescribeParameters>::SharedPtr describeParametersClient;
8182
rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedPtr getParametersClient;
8283
rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedPtr setParametersClient;
8384

8485
// callbacks for the results of the futures
8586
void nodeParametersReceived(const rclcpp::Client<rcl_interfaces::srv::ListParameters>::SharedFuture &future,
8687
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer);
88+
void parameterDescriptionsReceived(const rclcpp::Client<rcl_interfaces::srv::DescribeParameters>::SharedFuture &future,
89+
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer);
8790
void parameterValuesReceived(const rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedFuture &future,
88-
const std::vector<std::string> &parameterNames,
91+
const std::vector<rcl_interfaces::msg::ParameterDescriptor> &parameterDescriptors,
8992
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer);
9093
void parameterModificationResponseReceived(const rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedFuture &future,
9194
const std::string &parameterName,

include/utils.hpp

Lines changed: 54 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
#include <filesystem>
1515

1616
#include <GLFW/glfw3.h> // will drag system OpenGL headers
17+
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
1718

1819
struct Status {
1920
enum class Type { NONE, NO_NODES_AVAILABLE, PARAMETER_CHANGED, SERVICE_TIMEOUT };
@@ -44,6 +45,59 @@ void highlightedText(const std::string &text, std::size_t start, std::size_t end
4445
bool highlightedSelectableText(const std::string &text, std::size_t start, std::size_t end,
4546
const ImVec4 &highlightColor);
4647

48+
std::string getFormatStringFromStep(double step, int max_digits = 10);
49+
50+
/**
51+
* Checks if a given parameter has a range that is effectively bounded on both sides.
52+
*
53+
* @param param Parameter description.
54+
*/
55+
bool hasBoundedRange(const rcl_interfaces::msg::ParameterDescriptor& param);
56+
57+
/**
58+
* Checks if two double values are equal to within a specified tolerance.
59+
*
60+
* @param x First value.
61+
* @param y Second value.
62+
* @param ulp Maximum number of representable numbers between x and y.
63+
*/
64+
bool areDoublesEqual(double x, double y, double ulp = 100.0);
65+
66+
/**
67+
* Snaps and clamps a double value to a given range and step.
68+
*
69+
* Note: The value is snapped to the nearest integer number of steps from the 'from_value'
70+
* or clamped to the 'to_value'.
71+
*
72+
* The magnitude of the 'step' is used and the sign is ignored.
73+
*
74+
* If 'step' == 0 or if 'from_value' is == double::lowest(), the range is considered
75+
* continuous.
76+
*
77+
* @param value Input value.
78+
* @param from_value Range minimum.
79+
* @param to_value Range maximum.
80+
* @param step Step size.
81+
*/
82+
double snapToDoubleRange(double value, double from_value, double to_value, double step);
83+
84+
/**
85+
* Snaps and clamps an integer value to a given range and step.
86+
*
87+
* Note: The value is snapped to the nearest integer number of steps from the 'from_value'
88+
* or clamped to the 'to_value'.
89+
*
90+
* The magnitude of 'step' is used and the sign is ignored.
91+
*
92+
* If 'step' == 0, the step size is considered 1.
93+
*
94+
* @param value Input value.
95+
* @param from_value Range minimum.
96+
* @param to_value Range maximum.
97+
* @param step Step size.
98+
*/
99+
int64_t snapToIntegerRange(int64_t value, int64_t from_value, int64_t to_value, uint64_t step);
100+
47101
/**
48102
* Searches for the resource directory.
49103
* @param execPath Executable path.

package.xml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>rig_reconfigure</name>
5-
<version>1.5.0</version>
5+
<version>1.6.0</version>
66
<description>Standalone GUI tool for editing node parameters at runtime.</description>
77
<maintainer email="[email protected]">Team Spatzenhirn</maintainer>
88
<maintainer email="[email protected]">Jonas Otto</maintainer>
@@ -14,6 +14,7 @@
1414
<depend>libglfw3-dev</depend>
1515
<depend>rclcpp</depend>
1616
<depend>ament_index_cpp</depend>
17+
<depend>backward_ros</depend>
1718

1819
<export>
1920
<build_type>ament_cmake</build_type>

src/parameter_tree.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,8 @@ void ParameterTree::add(const std::shared_ptr<ParameterGroup> &curNode, const Tr
5353
curNode->subgroups.emplace_back(nextNode);
5454
}
5555

56-
add(nextNode, TreeElement(remainingName, parameter.fullPath, parameter.value));
56+
add(nextNode, TreeElement(remainingName, parameter.description, parameter.fullPath,
57+
parameter.value));
5758
}
5859

5960
std::shared_ptr<ParameterGroup> ParameterTree::getRoot() {

src/parameter_window.cpp

Lines changed: 57 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ constexpr auto TEXT_INPUT_EDITING_END_CHARACTERS = "\n";
2828

2929
static std::set<ImGuiID> visualizeParameters(ServiceWrapper &serviceWrapper,
3030
const std::shared_ptr<ParameterGroup> &parameterNode,
31-
std::size_t maxParamLength, std::size_t textfieldWidth,
31+
std::size_t maxParamLength,
3232
const std::string &filterString, bool expandAll = false);
3333

3434
void renderParameterWindow(const char *windowName, const std::string &curSelectedNode,
@@ -49,8 +49,6 @@ void renderParameterWindow(const char *windowName, const std::string &curSelecte
4949

5050
bool expandAllParameters = false;
5151

52-
const auto curWindowWidth = static_cast<int>(ImGui::GetWindowSize().x);
53-
5452
if (!curSelectedNode.empty()) {
5553
ImGui::Text("Parameters of '%s'", curSelectedNode.c_str());
5654
ImGui::Dummy(ImVec2(0.0F, 5.0F));
@@ -90,10 +88,8 @@ void renderParameterWindow(const char *windowName, const std::string &curSelecte
9088
ImGui::Dummy(ImVec2(0.0F, 10.0F));
9189

9290
const auto maxParamLength = filteredParameterTree.getMaxParamNameLength();
93-
const auto textfieldWidth = std::max(MIN_INPUT_TEXT_FIELD_WIDTH, curWindowWidth - static_cast<int>(maxParamLength) - TEXT_INPUT_FIELD_PADDING);
94-
9591
const auto ids = visualizeParameters(serviceWrapper, filteredParameterTree.getRoot(),
96-
maxParamLength, textfieldWidth, filteredParameterTree.getAppliedFilter(),
92+
maxParamLength, filteredParameterTree.getAppliedFilter(),
9793
expandAllParameters);
9894
treeNodeIDs.insert(ids.begin(), ids.end());
9995

@@ -108,10 +104,10 @@ void renderParameterWindow(const char *windowName, const std::string &curSelecte
108104
ImGui::End();
109105
}
110106

107+
111108
std::set<ImGuiID> visualizeParameters(ServiceWrapper &serviceWrapper,
112109
const std::shared_ptr<ParameterGroup> &parameterNode,
113110
const std::size_t maxParamLength,
114-
const std::size_t textfieldWidth,
115111
const std::string &filterString,
116112
const bool expandAll) {
117113
// required to store which of the text input fields is 'dirty' (has changes which have not yet been propagated to
@@ -132,7 +128,7 @@ std::set<ImGuiID> visualizeParameters(ServiceWrapper &serviceWrapper,
132128
return {};
133129
}
134130

135-
for (auto &[name, fullPath, value, highlightingStart, highlightingEnd] : parameterNode->parameters) {
131+
for (auto &[name, descriptor, fullPath, value, highlightingStart, highlightingEnd] : parameterNode->parameters) {
136132
std::string identifier = "##" + name;
137133

138134
// simple 'space' padding to avoid the need for a more complex layout with columns (the latter is still desired
@@ -154,11 +150,42 @@ std::set<ImGuiID> visualizeParameters(ServiceWrapper &serviceWrapper,
154150
ImGui::Text("%s", padding.c_str());
155151

156152
ImGui::SameLine();
157-
ImGui::PushItemWidth(static_cast<float>(textfieldWidth));
153+
ImGui::PushItemWidth(-FLT_MIN);
154+
155+
if (descriptor.read_only) {
156+
ImGui::BeginDisabled();
157+
}
158158

159159
if (std::holds_alternative<double>(value)) {
160-
ImGui::DragScalar(identifier.c_str(), ImGuiDataType_Double, &std::get<double>(value), 1.0F, nullptr,
161-
nullptr, "%.6g");
160+
if (hasBoundedRange(descriptor)) {
161+
double* min = &descriptor.floating_point_range[0].from_value;
162+
double* max = &descriptor.floating_point_range[0].to_value;
163+
double step = std::fabs(descriptor.floating_point_range[0].step);
164+
std::string format = getFormatStringFromStep(step);
165+
if(ImGui::SliderScalar(identifier.c_str(), ImGuiDataType_Double,
166+
&std::get<double>(value), min, max, format.c_str(),
167+
ImGuiSliderFlags_AlwaysClamp)) {
168+
std::get<double>(value) = snapToDoubleRange(std::get<double>(value), *min, *max, step);
169+
}
170+
}
171+
else if (!descriptor.floating_point_range.empty()) {
172+
double* min = &descriptor.floating_point_range[0].from_value;
173+
double* max = &descriptor.floating_point_range[0].to_value;
174+
double step = std::fabs(descriptor.floating_point_range[0].step);
175+
std::string format = getFormatStringFromStep(step);
176+
double speed = 1.0;
177+
if (step != 0.0 && !std::isnan(step)) {
178+
speed = step;
179+
}
180+
if(ImGui::DragScalar(identifier.c_str(), ImGuiDataType_Double, &std::get<double>(value),
181+
speed, min, max, format.c_str(), ImGuiSliderFlags_AlwaysClamp)) {
182+
std::get<double>(value) = snapToDoubleRange(std::get<double>(value), *min, *max, step);
183+
}
184+
}
185+
else {
186+
ImGui::DragScalar(identifier.c_str(), ImGuiDataType_Double, &std::get<double>(value),
187+
1.0, nullptr, nullptr, "%.6g");
188+
}
162189
if (ImGui::IsItemDeactivatedAfterEdit()) {
163190
serviceWrapper.pushRequest(
164191
std::make_shared<ParameterModificationRequest>(ROSParameter(fullPath, value)));
@@ -169,7 +196,19 @@ std::set<ImGuiID> visualizeParameters(ServiceWrapper &serviceWrapper,
169196
std::make_shared<ParameterModificationRequest>(ROSParameter(fullPath, value)));
170197
}
171198
} else if (std::holds_alternative<int>(value)) {
172-
ImGui::DragInt(identifier.c_str(), &std::get<int>(value));
199+
if (hasBoundedRange(descriptor)) {
200+
int min = descriptor.integer_range[0].from_value;
201+
int max = descriptor.integer_range[0].to_value;
202+
int step = descriptor.integer_range[0].step;
203+
204+
if(ImGui::SliderInt(identifier.c_str(), &std::get<int>(value), min, max, "%d",
205+
ImGuiSliderFlags_AlwaysClamp)) {
206+
std::get<int>(value) = snapToIntegerRange(std::get<int>(value), min, max, step);
207+
}
208+
}
209+
else {
210+
ImGui::DragInt(identifier.c_str(), &std::get<int>(value));
211+
}
173212
if (ImGui::IsItemDeactivatedAfterEdit()) {
174213
serviceWrapper.pushRequest(
175214
std::make_shared<ParameterModificationRequest>(ROSParameter(fullPath, value)));
@@ -200,6 +239,11 @@ std::set<ImGuiID> visualizeParameters(ServiceWrapper &serviceWrapper,
200239
std::make_shared<ParameterModificationRequest>(ROSParameter(fullPath, value)));
201240
}
202241
}
242+
243+
if (descriptor.read_only) {
244+
ImGui::EndDisabled();
245+
}
246+
203247
ImGui::PopItemWidth();
204248
}
205249

@@ -232,8 +276,7 @@ std::set<ImGuiID> visualizeParameters(ServiceWrapper &serviceWrapper,
232276
}
233277

234278
if (open) {
235-
const auto newWidth = textfieldWidth - TEXT_FIELD_WIDTH_REDUCTION_PER_LEVEL;
236-
auto subIDs = visualizeParameters(serviceWrapper, subgroup, maxParamLength, newWidth,
279+
auto subIDs = visualizeParameters(serviceWrapper, subgroup, maxParamLength,
237280
filterString, expandAll);
238281
nodeIDs.insert(subIDs.begin(), subIDs.end());
239282
ImGui::TreePop();

0 commit comments

Comments
 (0)