Skip to content

Commit adc969c

Browse files
committed
setting signing handle as false by default
1 parent 9216cb3 commit adc969c

26 files changed

Lines changed: 54 additions & 43 deletions

README.md

Lines changed: 23 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -233,7 +233,7 @@ def main() -> None:
233233
set_ros_loggers()
234234

235235
# Create a finite state machine (FSM)
236-
sm = StateMachine(outcomes=["outcome4"])
236+
sm = StateMachine(outcomes=["outcome4"], handle_sigint=True)
237237

238238
# Add states to the FSM
239239
sm.add_state(
@@ -370,7 +370,7 @@ def main() -> None:
370370
blackboard["msg1"] = "test1"
371371
blackboard["msg2"] = "test2"
372372

373-
sm = StateMachine(outcomes=[SUCCEED])
373+
sm = StateMachine(outcomes=[SUCCEED], handle_sigint=True)
374374
sm.add_state(
375375
"STATE1",
376376
Foo(),
@@ -534,7 +534,7 @@ def main() -> None:
534534
set_ros_loggers()
535535

536536
# Create a finite state machine (FSM)
537-
sm = StateMachine(outcomes=["outcome4"])
537+
sm = StateMachine(outcomes=["outcome4"], handle_sigint=True)
538538

539539
# Create states to run concurrently
540540
foo_state: State = FooState()
@@ -687,7 +687,7 @@ def main() -> None:
687687
set_ros_loggers()
688688

689689
# Create the state machine with 'SUCCEED' as the terminal outcome
690-
sm = StateMachine([SUCCEED])
690+
sm = StateMachine([SUCCEED], handle_sigint=True)
691691

692692
# Add the publishing state which loops until the condition is met
693693
sm.add_state(
@@ -823,7 +823,7 @@ def main() -> None:
823823
set_ros_loggers()
824824

825825
# Create a finite state machine (FSM)
826-
sm = StateMachine(outcomes=["outcome4"])
826+
sm = StateMachine(outcomes=["outcome4"], handle_sigint=True)
827827

828828
# Add states to the FSM
829829
sm.add_state(
@@ -987,7 +987,7 @@ def main() -> None:
987987
set_ros_loggers()
988988

989989
# Create a FSM
990-
sm = StateMachine(outcomes=["outcome4"])
990+
sm = StateMachine(outcomes=["outcome4"], handle_sigint=True)
991991

992992
# Add states
993993
sm.add_state(
@@ -1179,7 +1179,7 @@ def main() -> None:
11791179
set_ros_loggers()
11801180

11811181
# Create a finite state machine (FSM)
1182-
sm = StateMachine(outcomes=["outcome4"])
1182+
sm = StateMachine(outcomes=["outcome4"], handle_sigint=True)
11831183

11841184
# Add states to the FSM
11851185
sm.add_state(
@@ -1336,7 +1336,7 @@ def main() -> None:
13361336
set_ros_loggers()
13371337

13381338
# Create a finite state machine (FSM)
1339-
sm = StateMachine(outcomes=["outcome4"])
1339+
sm = StateMachine(outcomes=["outcome4"], handle_sigint=True)
13401340

13411341
# Add states to the FSM
13421342
sm.add_state(
@@ -1442,6 +1442,7 @@ def main() -> None:
14421442
get_package_share_directory("yasmin_demos"), "state_machines", "demo_1.xml"
14431443
)
14441444
)
1445+
sm.set_sigint_handler(True)
14451446

14461447
# Publish FSM information for visualization
14471448
viewer = YasminViewerPub(sm, "plugin_demo")
@@ -1606,7 +1607,7 @@ def main() -> None:
16061607
set_ros_loggers()
16071608

16081609
# Create state machines
1609-
sm = StateMachine(outcomes=[SUCCEED, ABORT, CANCEL])
1610+
sm = StateMachine(outcomes=[SUCCEED, ABORT, CANCEL], handle_sigint=True)
16101611
nav_sm = StateMachine(outcomes=[SUCCEED, ABORT, CANCEL])
16111612

16121613
# Add states to the state machine
@@ -1790,7 +1791,7 @@ int main(int argc, char *argv[]) {
17901791

17911792
// Create a state machine
17921793
auto sm = std::make_shared<yasmin::StateMachine>(
1793-
std::initializer_list<std::string>{"outcome4"});
1794+
std::initializer_list<std::string>{"outcome4"}, true);
17941795

17951796
// Add states to the state machine
17961797
sm->add_state("FOO", std::make_shared<FooState>(),
@@ -1912,7 +1913,8 @@ int main(int argc, char *argv[]) {
19121913

19131914
// Create a state machine
19141915
auto sm = std::make_shared<yasmin::StateMachine>(
1915-
std::initializer_list<std::string>{yasmin_ros::basic_outcomes::SUCCEED});
1916+
std::initializer_list<std::string>{yasmin_ros::basic_outcomes::SUCCEED},
1917+
true);
19161918

19171919
// Add states to the state machine
19181920
sm->add_state("STATE1", std::make_shared<FooState>(),
@@ -2080,7 +2082,7 @@ int main(int argc, char *argv[]) {
20802082

20812083
// Create a state machine
20822084
auto sm = std::make_shared<yasmin::StateMachine>(
2083-
std::initializer_list<std::string>{"outcome4"});
2085+
std::initializer_list<std::string>{"outcome4"}, true);
20842086

20852087
// Create states to run concurrently
20862088
auto foo_state = std::make_shared<FooState>();
@@ -2230,7 +2232,8 @@ int main(int argc, char *argv[]) {
22302232

22312233
// Create a state machine with a final outcome
22322234
auto sm = std::make_shared<yasmin::StateMachine>(
2233-
std::initializer_list<std::string>{yasmin_ros::basic_outcomes::SUCCEED});
2235+
std::initializer_list<std::string>{yasmin_ros::basic_outcomes::SUCCEED},
2236+
true);
22342237

22352238
// Add states to the state machine
22362239
sm->add_state("PUBLISHING_INT", std::make_shared<PublishIntState>(),
@@ -2373,7 +2376,7 @@ int main(int argc, char *argv[]) {
23732376

23742377
// Create a state machine with a final outcome
23752378
auto sm = std::make_shared<yasmin::StateMachine>(
2376-
std::initializer_list<std::string>{"outcome4"});
2379+
std::initializer_list<std::string>{"outcome4"}, true);
23772380

23782381
// Add states to the state machine
23792382
sm->add_state(
@@ -2542,7 +2545,7 @@ int main(int argc, char *argv[]) {
25422545

25432546
// Create a state machine with a specified outcome.
25442547
auto sm = std::make_shared<yasmin::StateMachine>(
2545-
std::initializer_list<std::string>{"outcome4"});
2548+
std::initializer_list<std::string>{"outcome4"}, true);
25462549

25472550
// Add states to the state machine.
25482551
sm->add_state("SETTING_INTS",
@@ -2743,7 +2746,7 @@ int main(int argc, char *argv[]) {
27432746

27442747
// Create the state machine
27452748
auto sm = std::make_shared<yasmin::StateMachine>(
2746-
std::initializer_list<std::string>{"outcome4"});
2749+
std::initializer_list<std::string>{"outcome4"}, true);
27472750

27482751
// Add states to the state machine
27492752
sm->add_state("CALLING_FIBONACCI", std::make_shared<FibonacciState>(),
@@ -2896,7 +2899,7 @@ int main(int argc, char *argv[]) {
28962899

28972900
// Create a state machine
28982901
auto sm = std::make_shared<yasmin::StateMachine>(
2899-
std::initializer_list<std::string>{"outcome4"});
2902+
std::initializer_list<std::string>{"outcome4"}, true);
29002903

29012904
// Add states to the state machine
29022905
sm->add_state("GETTING_PARAMETERS",
@@ -2991,6 +2994,7 @@ int main(int argc, char *argv[]) {
29912994

29922995
// Create the state machine from the XML file
29932996
auto sm = factory.create_sm_from_file(xml_file);
2997+
sm->set_sigint_handler(true);
29942998

29952999
// Execute the state machine
29963000
try {
@@ -3179,7 +3183,8 @@ int main(int argc, char *argv[]) {
31793183
auto sm = std::make_shared<yasmin::StateMachine>(
31803184
std::initializer_list<std::string>{yasmin_ros::basic_outcomes::SUCCEED,
31813185
yasmin_ros::basic_outcomes::ABORT,
3182-
yasmin_ros::basic_outcomes::CANCEL});
3186+
yasmin_ros::basic_outcomes::CANCEL},
3187+
true);
31833188
auto nav_sm = std::make_shared<yasmin::StateMachine>(
31843189
std::initializer_list<std::string>{yasmin_ros::basic_outcomes::SUCCEED,
31853190
yasmin_ros::basic_outcomes::ABORT,

yasmin/include/yasmin/state_machine.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ class StateMachine : public State {
6565
* machine.
6666
*/
6767
StateMachine(const std::set<std::string> &outcomes,
68-
bool handle_sigint = true);
68+
bool handle_sigint = false);
6969

7070
/**
7171
* @brief Construct a new StateMachine object.
@@ -76,7 +76,7 @@ class StateMachine : public State {
7676
* machine.
7777
*/
7878
StateMachine(const std::string &name, const std::set<std::string> &outcomes,
79-
bool handle_sigint = true);
79+
bool handle_sigint = false);
8080

8181
/**
8282
* @brief Destroy the StateMachine object.

yasmin/src/yasmin/state_machine_pybind11.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,10 +42,10 @@ PYBIND11_MODULE(state_machine, m) {
4242
std::set<std::string>(outcomes.begin(), outcomes.end()),
4343
handle_sigint);
4444
}),
45-
py::arg("outcomes"), py::arg("handle_sigint") = true)
45+
py::arg("outcomes"), py::arg("handle_sigint") = false)
4646
.def(py::init<const std::string &, const std::set<std::string> &, bool>(),
4747
py::arg("name"), py::arg("outcomes"),
48-
py::arg("handle_sigint") = true)
48+
py::arg("handle_sigint") = false)
4949
.def(py::init([](const std::string &name,
5050
const std::vector<std::string> &outcomes,
5151
bool handle_sigint) {
@@ -54,7 +54,7 @@ PYBIND11_MODULE(state_machine, m) {
5454
handle_sigint);
5555
}),
5656
py::arg("name"), py::arg("outcomes"),
57-
py::arg("handle_sigint") = true)
57+
py::arg("handle_sigint") = false)
5858
// Add destructor from StateMachine
5959
.def("__del__", [](yasmin::StateMachine *self) { delete self; })
6060
// Add state method with keep_alive to manage object lifetime

yasmin/yasmin/state_machine.pyi

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,11 +24,11 @@ class StateMachine(State):
2424
def __init__(self, outcomes: List[str], handle_sigint: bool = True) -> None: ...
2525
@overload
2626
def __init__(
27-
self, name: str, outcomes: Set[str], handle_sigint: bool = True
27+
self, name: str, outcomes: Set[str], handle_sigint: bool = False
2828
) -> None: ...
2929
@overload
3030
def __init__(
31-
self, name: str, outcomes: List[str], handle_sigint: bool = True
31+
self, name: str, outcomes: List[str], handle_sigint: bool = False
3232
) -> None: ...
3333
def add_state(
3434
self,

yasmin_demos/src/action_client_demo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -152,7 +152,7 @@ int main(int argc, char *argv[]) {
152152

153153
// Create the state machine
154154
auto sm = std::make_shared<yasmin::StateMachine>(
155-
std::initializer_list<std::string>{"outcome4"});
155+
std::initializer_list<std::string>{"outcome4"}, true);
156156

157157
// Add states to the state machine
158158
sm->add_state("CALLING_FIBONACCI", std::make_shared<FibonacciState>(),

yasmin_demos/src/concurrence_demo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ int main(int argc, char *argv[]) {
125125

126126
// Create a state machine
127127
auto sm = std::make_shared<yasmin::StateMachine>(
128-
std::initializer_list<std::string>{"outcome4"});
128+
std::initializer_list<std::string>{"outcome4"}, true);
129129

130130
// Create states to run concurrently
131131
auto foo_state = std::make_shared<FooState>();

yasmin_demos/src/factory_demo.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@ int main(int argc, char *argv[]) {
4343

4444
// Create the state machine from the XML file
4545
auto sm = factory.create_sm_from_file(xml_file);
46+
sm->set_sigint_handler(true);
4647

4748
// Publisher for visualizing the state machine
4849
yasmin_viewer::YasminViewerPub yasmin_pub(sm, "YASMIN_FACTORY_DEMO");

yasmin_demos/src/monitor_demo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ int main(int argc, char *argv[]) {
107107

108108
// Create a state machine with a final outcome
109109
auto sm = std::make_shared<yasmin::StateMachine>(
110-
std::initializer_list<std::string>{"outcome4"});
110+
std::initializer_list<std::string>{"outcome4"}, true);
111111

112112
// Add states to the state machine
113113
sm->add_state(

yasmin_demos/src/multiple_states_demo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ int main(int argc, char *argv[]) {
3333

3434
// Create a state machine
3535
auto sm = std::make_shared<yasmin::StateMachine>(
36-
std::initializer_list<std::string>{"outcome4"});
36+
std::initializer_list<std::string>{"outcome4"}, true);
3737

3838
// Add states to the state machine
3939
sm->add_state("FOO", std::make_shared<FooState>(),

yasmin_demos/src/parameters_demo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,7 @@ int main(int argc, char *argv[]) {
112112

113113
// Create a state machine
114114
auto sm = std::make_shared<yasmin::StateMachine>(
115-
std::initializer_list<std::string>{"outcome4"});
115+
std::initializer_list<std::string>{"outcome4"}, true);
116116

117117
// Add states to the state machine
118118
sm->add_state("GETTING_PARAMETERS",

0 commit comments

Comments
 (0)