Skip to content

Commit 087489a

Browse files
committed
creating alias for Parameters and fixing style of concurrence demo
1 parent 2575c00 commit 087489a

File tree

7 files changed

+63
-51
lines changed

7 files changed

+63
-51
lines changed

README.md

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -2059,15 +2059,15 @@ int main(int argc, char *argv[]) {
20592059

20602060
// Create concurrent state
20612061
auto concurrent_state = std::make_shared<yasmin::Concurrence>(
2062-
std::map<std::string, std::shared_ptr<yasmin::State>>{{"FOO", foo_state},
2063-
{"BAR", bar_state}},
2062+
yasmin::StateMap{
2063+
{"FOO", foo_state},
2064+
{"BAR", bar_state},
2065+
},
20642066
"defaulted",
2065-
yasmin::Concurrence::OutcomeMap{
2066-
{"outcome1",
2067-
yasmin::Concurrence::StateOutcomeMap{{"FOO", "outcome1"},
2068-
{"BAR", "outcome3"}}},
2069-
{"outcome2", yasmin::Concurrence::StateOutcomeMap{
2070-
{"FOO", "outcome2"}, {"BAR", "outcome3"}}}});
2067+
yasmin::OutcomeMap{
2068+
{"outcome1", {{"FOO", "outcome1"}, {"BAR", "outcome3"}}},
2069+
{"outcome2", {{"FOO", "outcome2"}, {"BAR", "outcome3"}}},
2070+
});
20712071

20722072
// Add concurrent state to the state machine
20732073
sm->add_state("CONCURRENCE", concurrent_state,
@@ -2875,7 +2875,7 @@ int main(int argc, char *argv[]) {
28752875
// Add states to the state machine
28762876
sm->add_state("GETTING_PARAMETERS",
28772877
std::make_shared<yasmin_ros::GetParametersState>(
2878-
std::map<std::string, std::any>{
2878+
yasmin_ros::GetParametersState::Parameters{
28792879
{"max_counter", 3},
28802880
{"counter_str", std::string("Counter")},
28812881
}),

docs/tutorials/cpp/concurrence_demo.html

Lines changed: 36 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -272,25 +272,25 @@ <h2>3. Create Concurrence Container</h2>
272272
yasmin_ros::set_ros_loggers();
273273
YASMIN_LOG_INFO("yasmin_concurrence_demo");
274274

275-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
276-
std::initializer_list&lt;std::string&gt;{"outcome4"}, true);
277-
278-
auto foo_state = std::make_shared&lt;FooState&gt;();
279-
auto bar_state = std::make_shared&lt;BarState&gt;();
280-
281-
auto concurrent_state = std::make_shared&lt;yasmin::Concurrence&gt;(
282-
std::map&lt;std::string, std::shared_ptr&lt;yasmin::State&gt;&gt;{
283-
{"FOO", foo_state},
284-
{"BAR", bar_state}
285-
},
286-
"defaulted",
287-
yasmin::Concurrence::OutcomeMap{
288-
{"outcome1",
289-
yasmin::Concurrence::StateOutcomeMap{{"FOO", "outcome1"},
290-
{"BAR", "outcome3"}}},
291-
{"outcome2", yasmin::Concurrence::StateOutcomeMap{
292-
{"FOO", "outcome2"}, {"BAR", "outcome3"}}}
293-
});</code></pre>
275+
// Create a state machine
276+
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
277+
std::initializer_list&lt;std::string&gt;{"outcome4"}, true);
278+
279+
// Create states to run concurrently
280+
auto foo_state = std::make_shared&lt;FooState&gt;();
281+
auto bar_state = std::make_shared&lt;BarState&gt;();
282+
283+
// Create concurrent state
284+
auto concurrent_state = std::make_shared&lt;yasmin::Concurrence&gt;(
285+
yasmin::StateMap{
286+
{"FOO", foo_state},
287+
{"BAR", bar_state},
288+
},
289+
"defaulted",
290+
yasmin::OutcomeMap{
291+
{"outcome1", {{"FOO", "outcome1"}, {"BAR", "outcome3"}}},
292+
{"outcome2", {{"FOO", "outcome2"}, {"BAR", "outcome3"}}},
293+
});</code></pre>
294294

295295
<h2>4. Add to State Machine</h2>
296296
<p>
@@ -301,23 +301,29 @@ <h2>4. Add to State Machine</h2>
301301
<code>outcome4</code>. This setup enables the demonstration to run
302302
through several concurrent executions before terminating.
303303
</p>
304-
<pre><code class="language-cpp">sm-&gt;add_state("CONCURRENCE", concurrent_state,
305-
{
306-
{"outcome1", "CONCURRENCE"},
307-
{"outcome2", "CONCURRENCE"},
308-
{"defaulted", "outcome4"},
309-
});
304+
<pre><code class="language-cpp"> // Add concurrent state to the state machine
305+
sm-&gt;add_state("CONCURRENCE", concurrent_state,
306+
{
307+
{"outcome1", "CONCURRENCE"},
308+
{"outcome2", "CONCURRENCE"},
309+
{"defaulted", "outcome4"},
310+
});
310311

311-
yasmin_viewer::YasminViewerPub yasmin_pub(sm, "YASMIN_CONCURRENCE_DEMO");
312+
// Publish state machine updates
313+
yasmin_viewer::YasminViewerPub yasmin_pub(sm, "YASMIN_CONCURRENCE_DEMO");
312314

313-
try {
315+
// Execute the state machine
316+
try {
314317
std::string outcome = (*sm.get())();
315318
YASMIN_LOG_INFO(outcome.c_str());
316-
} catch (const std::exception &e) {
319+
} catch (const std::exception &amp;e) {
317320
YASMIN_LOG_WARN(e.what());
318-
}
321+
}
322+
323+
rclcpp::shutdown();
319324

320-
rclcpp::shutdown();</code></pre>
325+
return 0;
326+
}</code></pre>
321327

322328
<h2>5. Run the Demo</h2>
323329
<p>

docs/tutorials/cpp/monitor_demo.html

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -200,7 +200,7 @@ <h2>1. Define the Monitor State</h2>
200200

201201
std::string
202202
monitor_handler(yasmin::Blackboard::SharedPtr blackboard,
203-
std::shared_ptr&lt;nav_msgs::msg::Odometry&gt; msg) {
203+
nav_msgs::msg::Odometry::SharedPtr msg) {
204204

205205
(void)blackboard;
206206

docs/tutorials/cpp/parameters_demo.html

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -258,7 +258,7 @@ <h2>2. Create the State Machine</h2>
258258
// Add states to the state machine
259259
sm-&gt;add_state("GETTING_PARAMETERS",
260260
std::make_shared&lt;yasmin_ros::GetParametersState&gt;(
261-
std::map&lt;std::string, std::any&gt;{
261+
yasmin_ros::GetParametersState::Parameters{
262262
{"max_counter", 3},
263263
{"counter_str", std::string("Counter")},
264264
}),

yasmin_demos/src/concurrence_demo.cpp

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -134,12 +134,15 @@ int main(int argc, char *argv[]) {
134134

135135
// Create concurrent state
136136
auto concurrent_state = std::make_shared<yasmin::Concurrence>(
137-
yasmin::StateMap{{"FOO", foo_state}, {"BAR", bar_state}}, "defaulted",
137+
yasmin::StateMap{
138+
{"FOO", foo_state},
139+
{"BAR", bar_state},
140+
},
141+
"defaulted",
138142
yasmin::OutcomeMap{
139-
{"outcome1",
140-
yasmin::StateOutcomeMap{{"FOO", "outcome1"}, {"BAR", "outcome3"}}},
141-
{"outcome2",
142-
yasmin::StateOutcomeMap{{"FOO", "outcome2"}, {"BAR", "outcome3"}}}});
143+
{"outcome1", {{"FOO", "outcome1"}, {"BAR", "outcome3"}}},
144+
{"outcome2", {{"FOO", "outcome2"}, {"BAR", "outcome3"}}},
145+
});
143146

144147
// Add concurrent state to the state machine
145148
sm->add_state("CONCURRENCE", concurrent_state,

yasmin_demos/src/parameters_demo.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
#include <iostream>
1818
#include <memory>
1919
#include <string>
20-
#include <unordered_map>
2120

2221
#include "rclcpp/rclcpp.hpp"
2322
#include "yasmin/logs.hpp"
@@ -119,7 +118,7 @@ int main(int argc, char *argv[]) {
119118
// Add states to the state machine
120119
sm->add_state("GETTING_PARAMETERS",
121120
std::make_shared<yasmin_ros::GetParametersState>(
122-
std::unordered_map<std::string, std::any>{
121+
yasmin_ros::GetParametersState::Parameters{
123122
{"max_counter", 3},
124123
{"counter_str", std::string("Counter")},
125124
}),

yasmin_ros/include/yasmin_ros/get_parameters_state.hpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,15 +36,19 @@ namespace yasmin_ros {
3636
*/
3737
class GetParametersState : public yasmin::State {
3838
public:
39+
/**
40+
* @brief Type alias for a map of parameters.
41+
*/
42+
using Parameters = std::unordered_map<std::string, std::any>;
43+
3944
/**
4045
* @brief Constructs a GetParametersState with a map of parameters.
4146
*
4247
* @param parameters A map of parameter names to their default values.
4348
* @param node A shared pointer to the ROS 2 node.
4449
*/
45-
GetParametersState(
46-
const std::unordered_map<std::string, std::any> &parameters,
47-
rclcpp::Node::SharedPtr node = nullptr);
50+
GetParametersState(const Parameters &parameters,
51+
rclcpp::Node::SharedPtr node = nullptr);
4852

4953
/**
5054
* @brief Executes the state to retrieve parameters.

0 commit comments

Comments
 (0)