Skip to content

Commit 6527072

Browse files
committed
Improving types macros by adding make functions (make_share, make_unique)
1 parent 03232df commit 6527072

34 files changed

+241
-263
lines changed

README.md

Lines changed: 68 additions & 81 deletions
Large diffs are not rendered by default.

docs/tutorials/cpp/action_client_demo.html

Lines changed: 10 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -184,25 +184,23 @@ <h2>1. Define the Action State</h2>
184184
std::bind(&FibonacciState::response_handler, this, _1, _2),
185185
std::bind(&FibonacciState::print_feedback, this, _1, _2)) {};
186186

187-
Fibonacci::Goal create_goal_handler(
188-
yasmin::Blackboard::SharedPtr blackboard) {
187+
Fibonacci::Goal
188+
create_goal_handler(yasmin::Blackboard::SharedPtr blackboard) {
189189

190190
auto goal = Fibonacci::Goal();
191191
goal.order = blackboard-&gt;get&lt;int&gt;("n");
192192
return goal;
193193
};
194194

195-
std::string
196-
response_handler(yasmin::Blackboard::SharedPtr blackboard,
197-
Fibonacci::Result::SharedPtr response) {
195+
std::string response_handler(yasmin::Blackboard::SharedPtr blackboard,
196+
Fibonacci::Result::SharedPtr response) {
198197

199198
blackboard-&gt;set&lt;std::vector&lt;int&gt;&gt;("fibo_res", response-&gt;sequence);
200199
return yasmin_ros::basic_outcomes::SUCCEED;
201200
};
202201

203-
void
204-
print_feedback(yasmin::Blackboard::SharedPtr blackboard,
205-
std::shared_ptr&lt;const Fibonacci::Feedback&gt; feedback) {
202+
void print_feedback(yasmin::Blackboard::SharedPtr blackboard,
203+
std::shared_ptr&lt;const Fibonacci::Feedback&gt; feedback) {
206204
(void)blackboard;
207205

208206
std::stringstream ss;
@@ -231,7 +229,6 @@ <h2>2. Create the State Machine</h2>
231229
first 10 Fibonacci numbers.
232230
</p>
233231
<pre><code class="language-cpp">int main(int argc, char *argv[]) {
234-
235232
// Initialize ROS 2
236233
rclcpp::init(argc, argv);
237234

@@ -240,18 +237,18 @@ <h2>2. Create the State Machine</h2>
240237
YASMIN_LOG_INFO("yasmin_action_client_demo");
241238

242239
// Create the state machine
243-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
240+
auto sm = yasmin::StateMachine::make_shared(
244241
std::initializer_list&lt;std::string&gt;{"outcome4"}, true);
245242

246243
// Add states to the state machine
247-
sm-&gt;add_state("CALLING_FIBONACCI", std::make_shared&lt;FibonacciState&gt;(),
244+
sm-&gt;add_state("CALLING_FIBONACCI", FibonacciState::make_shared(),
248245
{
249246
{yasmin_ros::basic_outcomes::SUCCEED, "PRINTING_RESULT"},
250247
{yasmin_ros::basic_outcomes::CANCEL, "outcome4"},
251248
{yasmin_ros::basic_outcomes::ABORT, "outcome4"},
252249
});
253250
sm-&gt;add_state("PRINTING_RESULT",
254-
std::make_shared&lt;yasmin::CbState&gt;(
251+
yasmin::CbState::make_shared(
255252
std::initializer_list&lt;std::string&gt;{
256253
yasmin_ros::basic_outcomes::SUCCEED},
257254
print_result),
@@ -263,8 +260,7 @@ <h2>2. Create the State Machine</h2>
263260
yasmin_viewer::YasminViewerPub yasmin_pub(sm, "YASMIN_ACTION_CLIENT_DEMO");
264261

265262
// Create an initial blackboard and set the Fibonacci order
266-
yasmin::Blackboard::SharedPtr blackboard =
267-
std::make_shared&lt;yasmin::Blackboard&gt;();
263+
yasmin::Blackboard::SharedPtr blackboard = yasmin::Blackboard::make_shared();
268264
blackboard-&gt;set&lt;int&gt;("n", 10);
269265

270266
// Execute the state machine

docs/tutorials/cpp/basic_fsm.html

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -176,7 +176,7 @@ <h2>1. Create the FooState</h2>
176176
/**
177177
* @brief Constructs a FooState object, initializing the counter.
178178
*/
179-
FooState() : yasmin::State({"outcome1", "outcome2"}), counter(0){};
179+
FooState() : yasmin::State({"outcome1", "outcome2"}), counter(0) {};
180180

181181
/**
182182
* @brief Executes the Foo state logic.
@@ -189,8 +189,7 @@ <h2>1. Create the FooState</h2>
189189
* @param blackboard Shared pointer to the blackboard for state communication.
190190
* @return std::string The outcome of the execution: "outcome1" or "outcome2".
191191
*/
192-
std::string
193-
execute(yasmin::Blackboard::SharedPtr blackboard) override {
192+
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
194193
YASMIN_LOG_INFO("Executing state FOO");
195194
std::this_thread::sleep_for(std::chrono::seconds(3));
196195

@@ -240,8 +239,7 @@ <h2>2. Create the BarState</h2>
240239
* @param blackboard Shared pointer to the blackboard for state communication.
241240
* @return std::string The outcome of the execution: "outcome3".
242241
*/
243-
std::string
244-
execute(yasmin::Blackboard::SharedPtr blackboard) override {
242+
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
245243
YASMIN_LOG_INFO("Executing state BAR");
246244
std::this_thread::sleep_for(std::chrono::seconds(3));
247245

@@ -275,16 +273,16 @@ <h2>3. Main Function</h2>
275273
YASMIN_LOG_INFO("yasmin_demo");
276274

277275
// Create a state machine
278-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
276+
auto sm = yasmin::StateMachine::make_shared(
279277
std::initializer_list&lt;std::string&gt;{"outcome4"}, true);
280278

281279
// Add states to the state machine
282-
sm-&gt;add_state("FOO", std::make_shared&lt;FooState&gt;(),
280+
sm-&gt;add_state("FOO", FooState::make_shared(),
283281
{
284282
{"outcome1", "BAR"},
285283
{"outcome2", "outcome4"},
286284
});
287-
sm-&gt;add_state("BAR", std::make_shared&lt;BarState&gt;(),
285+
sm-&gt;add_state("BAR", BarState::make_shared(),
288286
{
289287
{"outcome3", "FOO"},
290288
});

docs/tutorials/cpp/concurrence_demo.html

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -191,8 +191,7 @@ <h2>1. Create the FooState</h2>
191191
FooState()
192192
: yasmin::State({"outcome1", "outcome2", "outcome3"}), counter(0) {};
193193

194-
std::string
195-
execute(yasmin::Blackboard::SharedPtr blackboard) override {
194+
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
196195
YASMIN_LOG_INFO("Executing state FOO");
197196
std::this_thread::sleep_for(std::chrono::seconds(2));
198197

@@ -232,8 +231,7 @@ <h2>2. Create the BarState</h2>
232231
public:
233232
BarState() : yasmin::State({"outcome3"}) {}
234233

235-
std::string
236-
execute(yasmin::Blackboard::SharedPtr blackboard) override {
234+
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
237235
YASMIN_LOG_INFO("Executing state BAR");
238236
std::this_thread::sleep_for(std::chrono::seconds(4));
239237

@@ -273,15 +271,15 @@ <h2>3. Create Concurrence Container</h2>
273271
YASMIN_LOG_INFO("yasmin_concurrence_demo");
274272

275273
// Create a state machine
276-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
274+
auto sm = yasmin::StateMachine::make_shared(
277275
std::initializer_list&lt;std::string&gt;{"outcome4"}, true);
278276

279277
// 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;();
278+
auto foo_state = FooState::make_shared();
279+
auto bar_state = BarState::make_shared();
282280

283281
// Create concurrent state
284-
auto concurrent_state = std::make_shared&lt;yasmin::Concurrence&gt;(
282+
auto concurrent_state = yasmin::Concurrence::make_shared(
285283
yasmin::StateMap{
286284
{"FOO", foo_state},
287285
{"BAR", bar_state},

docs/tutorials/cpp/monitor_demo.html

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -198,9 +198,8 @@ <h2>1. Define the Monitor State</h2>
198198
this-&gt;times = times;
199199
};
200200

201-
std::string
202-
monitor_handler(yasmin::Blackboard::SharedPtr blackboard,
203-
nav_msgs::msg::Odometry::SharedPtr msg) {
201+
std::string monitor_handler(yasmin::Blackboard::SharedPtr blackboard,
202+
nav_msgs::msg::Odometry::SharedPtr msg) {
204203

205204
(void)blackboard;
206205

@@ -243,12 +242,12 @@ <h2>2. Create the State Machine</h2>
243242
YASMIN_LOG_INFO("yasmin_monitor_demo");
244243

245244
// Create a state machine with a final outcome
246-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
245+
auto sm = yasmin::StateMachine::make_shared(
247246
std::initializer_list&lt;std::string&gt;{"outcome4"}, true);
248247

249248
// Add states to the state machine
250249
sm-&gt;add_state(
251-
"PRINTING_ODOM", std::make_shared&lt;PrintOdometryState&gt;(5),
250+
"PRINTING_ODOM", PrintOdometryState::make_shared(5),
252251
{
253252
{"outcome1",
254253
"PRINTING_ODOM"}, // Transition back to itself on outcome1

docs/tutorials/cpp/nav2_demo.html

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -262,8 +262,7 @@ <h2>Source Code</h2>
262262
}
263263
};
264264

265-
std::string
266-
create_waypoints(yasmin::Blackboard::SharedPtr blackboard) {
265+
std::string create_waypoints(yasmin::Blackboard::SharedPtr blackboard) {
267266
std::map&lt;std::string, std::vector&lt;double&gt;&gt; waypoints = {
268267
{"entrance", {1.25, 6.30, -0.78, 0.67}},
269268
{"bathroom", {4.89, 1.64, 0.0, 1.0}},
@@ -297,8 +296,7 @@ <h2>Source Code</h2>
297296
return yasmin_ros::basic_outcomes::SUCCEED;
298297
}
299298

300-
std::string
301-
get_next_waypoint(yasmin::Blackboard::SharedPtr blackboard) {
299+
std::string get_next_waypoint(yasmin::Blackboard::SharedPtr blackboard) {
302300
auto random_waypoints =
303301
blackboard-&gt;get&lt;std::vector&lt;std::string&gt;&gt;("random_waypoints");
304302
auto waypoints =
@@ -332,26 +330,26 @@ <h2>Source Code</h2>
332330
rclcpp::init(argc, argv);
333331
yasmin_ros::set_ros_loggers();
334332

335-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
333+
auto sm = yasmin::StateMachine::make_shared(
336334
std::initializer_list&lt;std::string&gt;{yasmin_ros::basic_outcomes::SUCCEED,
337335
yasmin_ros::basic_outcomes::ABORT,
338336
yasmin_ros::basic_outcomes::CANCEL},
339337
true);
340-
auto nav_sm = std::make_shared&lt;yasmin::StateMachine&gt;(
338+
auto nav_sm = yasmin::StateMachine::make_shared(
341339
std::initializer_list&lt;std::string&gt;{yasmin_ros::basic_outcomes::SUCCEED,
342340
yasmin_ros::basic_outcomes::ABORT,
343341
yasmin_ros::basic_outcomes::CANCEL});
344342

345343
sm-&gt;add_state(
346344
"CREATING_WAYPOINTS",
347-
std::make_shared&lt;yasmin::CbState&gt;(
345+
yasmin::CbState::make_shared(
348346
std::initializer_list&lt;std::string&gt;{
349347
yasmin_ros::basic_outcomes::SUCCEED},
350348
create_waypoints),
351349
std::map&lt;std::string, std::string&gt;{
352350
{yasmin_ros::basic_outcomes::SUCCEED, "TAKING_RANDOM_WAYPOINTS"}});
353351
sm-&gt;add_state("TAKING_RANDOM_WAYPOINTS",
354-
std::make_shared&lt;yasmin::CbState&gt;(
352+
yasmin::CbState::make_shared(
355353
std::initializer_list&lt;std::string&gt;{
356354
yasmin_ros::basic_outcomes::SUCCEED},
357355
take_random_waypoint),
@@ -360,13 +358,13 @@ <h2>Source Code</h2>
360358

361359
nav_sm-&gt;add_state(
362360
"GETTING_NEXT_WAYPOINT",
363-
std::make_shared&lt;yasmin::CbState&gt;(
361+
yasmin::CbState::make_shared(
364362
std::initializer_list&lt;std::string&gt;{END, HAS_NEXT}, get_next_waypoint),
365363
std::map&lt;std::string, std::string&gt;{
366364
{END, yasmin_ros::basic_outcomes::SUCCEED},
367365
{HAS_NEXT, "NAVIGATING"}});
368366
nav_sm-&gt;add_state(
369-
"NAVIGATING", std::make_shared&lt;Nav2State&gt;(),
367+
"NAVIGATING", Nav2State::make_shared(),
370368
std::map&lt;std::string, std::string&gt;{
371369
{yasmin_ros::basic_outcomes::SUCCEED, "GETTING_NEXT_WAYPOINT"},
372370
{yasmin_ros::basic_outcomes::CANCEL,
@@ -385,7 +383,7 @@ <h2>Source Code</h2>
385383

386384
yasmin_viewer::YasminViewerPub yasmin_pub(sm, "YASMIN_NAV2_DEMO");
387385

388-
auto blackboard = std::make_shared&lt;yasmin::Blackboard&gt;();
386+
auto blackboard = yasmin::Blackboard::make_shared();
389387
blackboard-&gt;set&lt;int&gt;("waypoints_num", 2);
390388

391389
try {

docs/tutorials/cpp/parameters_demo.html

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -194,8 +194,7 @@ <h2>1. Define the States</h2>
194194

195195
FooState() : yasmin::State({"outcome1", "outcome2"}), counter(0) {};
196196

197-
std::string
198-
execute(yasmin::Blackboard::SharedPtr blackboard) override {
197+
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
199198
YASMIN_LOG_INFO("Executing state FOO");
200199
std::this_thread::sleep_for(std::chrono::seconds(3));
201200

@@ -216,8 +215,7 @@ <h2>1. Define the States</h2>
216215
public:
217216
BarState() : yasmin::State({"outcome3"}) {}
218217

219-
std::string
220-
execute(yasmin::Blackboard::SharedPtr blackboard) override {
218+
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
221219
YASMIN_LOG_INFO("Executing state BAR");
222220
std::this_thread::sleep_for(std::chrono::seconds(3));
223221

@@ -252,12 +250,12 @@ <h2>2. Create the State Machine</h2>
252250
YASMIN_LOG_INFO("yasmin_parameters_demo");
253251

254252
// Create a state machine
255-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
253+
auto sm = yasmin::StateMachine::make_shared(
256254
std::initializer_list&lt;std::string&gt;{"outcome4"}, true);
257255

258256
// Add states to the state machine
259257
sm-&gt;add_state("GETTING_PARAMETERS",
260-
std::make_shared&lt;yasmin_ros::GetParametersState&gt;(
258+
yasmin_ros::GetParametersState::make_shared(
261259
yasmin_ros::GetParametersState::Parameters{
262260
{"max_counter", 3},
263261
{"counter_str", std::string("Counter")},
@@ -266,12 +264,12 @@ <h2>2. Create the State Machine</h2>
266264
{yasmin_ros::basic_outcomes::SUCCEED, "FOO"},
267265
{yasmin_ros::basic_outcomes::ABORT, "outcome4"},
268266
});
269-
sm-&gt;add_state("FOO", std::make_shared&lt;FooState&gt;(),
267+
sm-&gt;add_state("FOO", FooState::make_shared(),
270268
{
271269
{"outcome1", "BAR"},
272270
{"outcome2", "outcome4"},
273271
});
274-
sm-&gt;add_state("BAR", std::make_shared&lt;BarState&gt;(),
272+
sm-&gt;add_state("BAR", BarState::make_shared(),
275273
{
276274
{"outcome3", "FOO"},
277275
});

docs/tutorials/cpp/publisher_demo.html

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -216,8 +216,7 @@ <h2>2. Create the State Machine</h2>
216216
before completing. This pattern is useful for sending sequences of
217217
commands, periodic status updates, or controlled test data generation.
218218
</p>
219-
<pre><code class="language-cpp">std::string
220-
check_count(yasmin::Blackboard::SharedPtr blackboard) {
219+
<pre><code class="language-cpp">std::string check_count(yasmin::Blackboard::SharedPtr blackboard) {
221220

222221
// Sleep for 1 second to simulate some processing time
223222
rclcpp::sleep_for(std::chrono::seconds(1));
@@ -239,18 +238,18 @@ <h2>2. Create the State Machine</h2>
239238
YASMIN_LOG_INFO("yasmin_publisher_demo");
240239

241240
// Create a state machine with a final outcome
242-
auto sm = std::make_shared&lt;yasmin::StateMachine&gt;(
241+
auto sm = yasmin::StateMachine::make_shared(
243242
std::initializer_list&lt;std::string&gt;{yasmin_ros::basic_outcomes::SUCCEED},
244243
true);
245244

246245
// Add states to the state machine
247-
sm-&gt;add_state("PUBLISHING_INT", std::make_shared&lt;PublishIntState&gt;(),
246+
sm-&gt;add_state("PUBLISHING_INT", PublishIntState::make_shared(),
248247
{
249248
{yasmin_ros::basic_outcomes::SUCCEED,
250249
"CHECKINNG_COUNTS"}, // Transition back to itself
251250
});
252251
sm-&gt;add_state("CHECKINNG_COUNTS",
253-
std::make_shared&lt;yasmin::CbState&gt;(
252+
yasmin::CbState::make_shared(
254253
std::initializer_list&lt;std::string&gt;{"outcome1", "outcome2"},
255254
check_count),
256255
{{"outcome1", yasmin_ros::basic_outcomes::SUCCEED},
@@ -261,7 +260,7 @@ <h2>2. Create the State Machine</h2>
261260

262261
// Execute the state machine
263262
yasmin::Blackboard::SharedPtr blackboard =
264-
std::make_shared&lt;yasmin::Blackboard&gt;();
263+
yasmin::Blackboard::make_shared();
265264
blackboard-&gt;set&lt;int&gt;("counter", 0);
266265
blackboard-&gt;set&lt;int&gt;("max_count", 10);
267266
try {

0 commit comments

Comments
 (0)