Lifecycle refactor (#298)
* no static initialization of states anymore * make transition labels more descriptive * introduce labeled keys * define default transition keys * fix memory management * introduce service for transition graph * export transition keys * remove keys, transition id unique, label ambiguous * semicolon for macro call
This commit is contained in:
parent
9d4b1c9912
commit
5e3d4be720
13 changed files with 933 additions and 659 deletions
|
@ -24,8 +24,6 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
typedef uint8_t rcl_lifecycle_transition_key_t;
|
||||
|
||||
typedef struct rcl_lifecycle_transition_t rcl_lifecycle_transition_t;
|
||||
|
||||
typedef struct rcl_lifecycle_state_t
|
||||
|
@ -33,16 +31,6 @@ typedef struct rcl_lifecycle_state_t
|
|||
const char * label;
|
||||
unsigned int id;
|
||||
|
||||
// a valid key is a generic identifier for deciding
|
||||
// which transitions to trigger.
|
||||
// This serves the purpose of hiding a unique ID from
|
||||
// users prospective.
|
||||
// e.g. shutdown
|
||||
// the concrete transition for the state "unconfigured"
|
||||
// is "unconfigured_shutdown". However, the user only specifies
|
||||
// "shutdown". So we register the "unconfigured_shutdown"
|
||||
// transition with the impuls "shutdown".
|
||||
rcl_lifecycle_transition_key_t * valid_transition_keys;
|
||||
rcl_lifecycle_transition_t * valid_transitions;
|
||||
unsigned int valid_transition_size;
|
||||
} rcl_lifecycle_state_t;
|
||||
|
@ -71,6 +59,7 @@ typedef struct rcl_lifecycle_com_interface_t
|
|||
rcl_service_t srv_get_state;
|
||||
rcl_service_t srv_get_available_states;
|
||||
rcl_service_t srv_get_available_transitions;
|
||||
rcl_service_t srv_get_transition_graph;
|
||||
} rcl_lifecycle_com_interface_t;
|
||||
|
||||
typedef struct rcl_lifecycle_state_machine_t
|
||||
|
|
|
@ -12,8 +12,8 @@
|
|||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
|
||||
#ifndef DEFAULT_STATE_MACHINE_H_
|
||||
#define DEFAULT_STATE_MACHINE_H_
|
||||
#ifndef RCL_LIFECYCLE__DEFAULT_STATE_MACHINE_H_
|
||||
#define RCL_LIFECYCLE__DEFAULT_STATE_MACHINE_H_
|
||||
|
||||
#include "rcl/macros.h"
|
||||
#include "rcl/types.h"
|
||||
|
@ -26,6 +26,16 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_configure_label;
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_cleanup_label;
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_activate_label;
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_deactivate_label;
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_shutdown_label;
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_transition_success_label;
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_transition_failure_label;
|
||||
RCL_LIFECYCLE_PUBLIC extern const char * rcl_lifecycle_transition_error_label;
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
|
@ -36,4 +46,4 @@ rcl_lifecycle_init_default_state_machine(
|
|||
}
|
||||
#endif
|
||||
|
||||
#endif // DEFAULT_STATE_MACHINE_H_
|
||||
#endif // RCL_LIFECYCLE__DEFAULT_STATE_MACHINE_H_
|
|
@ -23,6 +23,7 @@ extern "C"
|
|||
#include <stdbool.h>
|
||||
|
||||
#include "rcl_lifecycle/data_types.h"
|
||||
#include "rcl_lifecycle/default_state_machine.h"
|
||||
#include "rcl_lifecycle/visibility_control.h"
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC
|
||||
|
@ -89,6 +90,7 @@ rcl_lifecycle_state_machine_init(
|
|||
const rosidl_service_type_support_t * ts_srv_get_state,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_states,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_transitions,
|
||||
const rosidl_service_type_support_t * ts_srv_get_transition_graph,
|
||||
bool default_states,
|
||||
const rcl_allocator_t * allocator);
|
||||
|
||||
|
@ -109,27 +111,32 @@ rcl_lifecycle_state_machine_is_initialized(
|
|||
RCL_LIFECYCLE_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
const rcl_lifecycle_transition_t *
|
||||
rcl_lifecycle_is_valid_callback_transition(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
rcl_lifecycle_transition_key_t key);
|
||||
rcl_lifecycle_get_transition_by_id(
|
||||
const rcl_lifecycle_state_t * state,
|
||||
uint8_t id);
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
const rcl_lifecycle_transition_t *
|
||||
rcl_lifecycle_get_transition_by_label(
|
||||
const rcl_lifecycle_state_t * state,
|
||||
const char * label);
|
||||
|
||||
/// Execute a transition
|
||||
/*
|
||||
* Important note for \param key here:
|
||||
* This is meant as feedback from the high level
|
||||
* callback associated with this transition.
|
||||
* The key is the index for the valid transitions
|
||||
* associated with the current state.
|
||||
* This key may either be a valid external stimuli
|
||||
* such as "configure" or direct return codes from
|
||||
* callbacks such as RCL_LIFECYCLE_RET_OK et. al.
|
||||
*/
|
||||
RCL_LIFECYCLE_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_lifecycle_trigger_transition(
|
||||
rcl_lifecycle_trigger_transition_by_id(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
rcl_lifecycle_transition_key_t key, bool publish_notification);
|
||||
uint8_t id,
|
||||
bool publish_notification);
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_lifecycle_trigger_transition_by_label(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
const char * label,
|
||||
bool publish_notification);
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC
|
||||
void
|
||||
|
|
|
@ -57,7 +57,6 @@ rcl_ret_t
|
|||
rcl_lifecycle_register_transition(
|
||||
rcl_lifecycle_transition_map_t * transition_map,
|
||||
rcl_lifecycle_transition_t transition,
|
||||
rcl_lifecycle_transition_key_t key,
|
||||
const rcl_allocator_t * allocator);
|
||||
|
||||
RCL_LIFECYCLE_PUBLIC
|
||||
|
|
|
@ -42,6 +42,7 @@ static const char * srv_change_state_service = "~/change_state";
|
|||
static const char * srv_get_state_service = "~/get_state";
|
||||
static const char * srv_get_available_states_service = "~/get_available_states";
|
||||
static const char * srv_get_available_transitions_service = "~/get_available_transitions";
|
||||
static const char * srv_get_transition_graph = "~/get_transition_graph";
|
||||
|
||||
rcl_lifecycle_com_interface_t
|
||||
rcl_lifecycle_get_zero_initialized_com_interface()
|
||||
|
@ -53,6 +54,7 @@ rcl_lifecycle_get_zero_initialized_com_interface()
|
|||
com_interface.srv_get_state = rcl_get_zero_initialized_service();
|
||||
com_interface.srv_get_available_states = rcl_get_zero_initialized_service();
|
||||
com_interface.srv_get_available_transitions = rcl_get_zero_initialized_service();
|
||||
com_interface.srv_get_transition_graph = rcl_get_zero_initialized_service();
|
||||
return com_interface;
|
||||
}
|
||||
|
||||
|
@ -65,6 +67,7 @@ rcl_lifecycle_com_interface_init(
|
|||
const rosidl_service_type_support_t * ts_srv_get_state,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_states,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_transitions,
|
||||
const rosidl_service_type_support_t * ts_srv_get_transition_graph,
|
||||
const rcl_allocator_t * allocator)
|
||||
{
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator())
|
||||
|
@ -77,6 +80,8 @@ rcl_lifecycle_com_interface_init(
|
|||
ts_srv_get_available_states, RCL_RET_INVALID_ARGUMENT, *allocator)
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(
|
||||
ts_srv_get_available_transitions, RCL_RET_INVALID_ARGUMENT, *allocator)
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(
|
||||
ts_srv_get_transition_graph, RCL_RET_INVALID_ARGUMENT, *allocator)
|
||||
|
||||
// initialize publisher
|
||||
{
|
||||
|
@ -141,6 +146,17 @@ rcl_lifecycle_com_interface_init(
|
|||
}
|
||||
}
|
||||
|
||||
// initialize get transition graph service
|
||||
{
|
||||
rcl_service_options_t service_options = rcl_service_get_default_options();
|
||||
rcl_ret_t ret = rcl_service_init(
|
||||
&com_interface->srv_get_transition_graph, node_handle,
|
||||
ts_srv_get_transition_graph, srv_get_transition_graph, &service_options);
|
||||
|
||||
if (ret != RCL_RET_OK) {
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
return RCL_RET_OK;
|
||||
|
||||
fail:
|
||||
|
@ -160,6 +176,10 @@ fail:
|
|||
RCUTILS_LOG_ERROR_NAMED(
|
||||
ROS_PACKAGE_NAME, "Failed to destroy get_available_transitions service");
|
||||
}
|
||||
if (RCL_RET_OK != rcl_service_fini(&com_interface->srv_get_transition_graph, node_handle)) {
|
||||
RCUTILS_LOG_ERROR_NAMED(
|
||||
ROS_PACKAGE_NAME, "Failed to destroy get_transition_graph service");
|
||||
}
|
||||
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
|
@ -171,6 +191,15 @@ rcl_lifecycle_com_interface_fini(
|
|||
{
|
||||
rcl_ret_t fcn_ret = RCL_RET_OK;
|
||||
|
||||
// destroy get transition graph srv
|
||||
{
|
||||
rcl_ret_t ret = rcl_service_fini(
|
||||
&com_interface->srv_get_transition_graph, node_handle);
|
||||
if (ret != RCL_RET_OK) {
|
||||
fcn_ret = RCL_RET_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
// destroy get available transitions srv
|
||||
{
|
||||
rcl_ret_t ret = rcl_service_fini(
|
||||
|
|
|
@ -37,6 +37,7 @@ rcl_lifecycle_com_interface_init(
|
|||
const rosidl_service_type_support_t * ts_srv_get_state,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_states,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_transitions,
|
||||
const rosidl_service_type_support_t * ts_srv_get_transition_graph,
|
||||
const rcl_allocator_t * allocator);
|
||||
|
||||
rcl_ret_t
|
||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -17,6 +17,8 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
#include "rcl_lifecycle/rcl_lifecycle.h"
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
@ -27,12 +29,10 @@ extern "C"
|
|||
#include "rcutils/logging_macros.h"
|
||||
#include "rcutils/strdup.h"
|
||||
|
||||
#include "rcl_lifecycle/rcl_lifecycle.h"
|
||||
#include "rcl_lifecycle/default_state_machine.h"
|
||||
#include "rcl_lifecycle/transition_map.h"
|
||||
|
||||
#include "com_interface.h" // NOLINT
|
||||
#include "default_state_machine.h" // NOLINT
|
||||
#include "states.h" // NOLINT
|
||||
#include "./com_interface.h"
|
||||
|
||||
rcl_lifecycle_state_t
|
||||
rcl_lifecycle_get_zero_initialized_state()
|
||||
|
@ -192,6 +192,7 @@ rcl_lifecycle_state_machine_init(
|
|||
const rosidl_service_type_support_t * ts_srv_get_state,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_states,
|
||||
const rosidl_service_type_support_t * ts_srv_get_available_transitions,
|
||||
const rosidl_service_type_support_t * ts_srv_get_transition_graph,
|
||||
bool default_states,
|
||||
const rcl_allocator_t * allocator)
|
||||
{
|
||||
|
@ -205,7 +206,7 @@ rcl_lifecycle_state_machine_init(
|
|||
&state_machine->com_interface, node_handle,
|
||||
ts_pub_notify,
|
||||
ts_srv_change_state, ts_srv_get_state,
|
||||
ts_srv_get_available_states, ts_srv_get_available_transitions,
|
||||
ts_srv_get_available_states, ts_srv_get_available_transitions, ts_srv_get_transition_graph,
|
||||
allocator);
|
||||
if (ret != RCL_RET_OK) {
|
||||
return RCL_RET_ERROR;
|
||||
|
@ -277,45 +278,57 @@ rcl_lifecycle_state_machine_is_initialized(const rcl_lifecycle_state_machine_t *
|
|||
}
|
||||
|
||||
const rcl_lifecycle_transition_t *
|
||||
rcl_lifecycle_is_valid_transition(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
rcl_lifecycle_transition_key_t key)
|
||||
rcl_lifecycle_get_transition_by_id(
|
||||
const rcl_lifecycle_state_t * state,
|
||||
uint8_t id)
|
||||
{
|
||||
unsigned int current_id = state_machine->current_state->id;
|
||||
const rcl_lifecycle_state_t * current_state = rcl_lifecycle_get_state(
|
||||
&state_machine->transition_map, current_id);
|
||||
RCL_CHECK_FOR_NULL_WITH_MSG(state,
|
||||
"state pointer is null", return NULL, rcl_get_default_allocator());
|
||||
|
||||
RCL_CHECK_FOR_NULL_WITH_MSG(current_state,
|
||||
"rcl_lifecycle_get_state returns NULL", return NULL, rcl_get_default_allocator());
|
||||
|
||||
for (unsigned int i = 0; i < current_state->valid_transition_size; ++i) {
|
||||
if (current_state->valid_transition_keys[i] == key) {
|
||||
return ¤t_state->valid_transitions[i];
|
||||
for (unsigned int i = 0; i < state->valid_transition_size; ++i) {
|
||||
if (state->valid_transitions[i].id == id) {
|
||||
return &state->valid_transitions[i];
|
||||
}
|
||||
}
|
||||
|
||||
RCUTILS_LOG_WARN_NAMED(
|
||||
ROS_PACKAGE_NAME,
|
||||
"No callback transition matching %d found for current state %s",
|
||||
key, state_machine->current_state->label);
|
||||
"No transition matching %d found for current state %s",
|
||||
id, state->label);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
const rcl_lifecycle_transition_t *
|
||||
rcl_lifecycle_get_transition_by_label(
|
||||
const rcl_lifecycle_state_t * state,
|
||||
const char * label)
|
||||
{
|
||||
RCL_CHECK_FOR_NULL_WITH_MSG(state,
|
||||
"state pointer is null", return NULL, rcl_get_default_allocator());
|
||||
|
||||
for (unsigned int i = 0; i < state->valid_transition_size; ++i) {
|
||||
if (strcmp(state->valid_transitions[i].label, label) == 0) {
|
||||
return &state->valid_transitions[i];
|
||||
}
|
||||
}
|
||||
|
||||
RCUTILS_LOG_WARN_NAMED(
|
||||
ROS_PACKAGE_NAME,
|
||||
"No transition matching %s found for current state %s",
|
||||
label, state->label);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_ret_t
|
||||
rcl_lifecycle_trigger_transition(
|
||||
_trigger_transition(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
rcl_lifecycle_transition_key_t key, bool publish_notification)
|
||||
const rcl_lifecycle_transition_t * transition,
|
||||
bool publish_notification)
|
||||
{
|
||||
const rcl_lifecycle_transition_t * transition =
|
||||
rcl_lifecycle_is_valid_transition(state_machine, key);
|
||||
|
||||
// If we have a faulty transition pointer
|
||||
if (!transition) {
|
||||
RCUTILS_LOG_ERROR_NAMED(
|
||||
ROS_PACKAGE_NAME,
|
||||
"No transition found for node %s with key %d",
|
||||
state_machine->current_state->label, key);
|
||||
RCL_SET_ERROR_MSG("Transition is not registered.", rcl_get_default_allocator());
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
|
@ -326,6 +339,7 @@ rcl_lifecycle_trigger_transition(
|
|||
return RCL_RET_ERROR;
|
||||
}
|
||||
state_machine->current_state = transition->goal;
|
||||
|
||||
if (publish_notification) {
|
||||
rcl_ret_t ret = rcl_lifecycle_com_interface_publish_notification(
|
||||
&state_machine->com_interface, transition->start, state_machine->current_state);
|
||||
|
@ -338,6 +352,39 @@ rcl_lifecycle_trigger_transition(
|
|||
return RCL_RET_OK;
|
||||
}
|
||||
|
||||
rcl_ret_t
|
||||
rcl_lifecycle_trigger_transition_by_id(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
uint8_t id,
|
||||
bool publish_notification)
|
||||
{
|
||||
if (!state_machine) {
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "state machine pointer is null");
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
|
||||
const rcl_lifecycle_transition_t * transition =
|
||||
rcl_lifecycle_get_transition_by_id(state_machine->current_state, id);
|
||||
|
||||
return _trigger_transition(state_machine, transition, publish_notification);
|
||||
}
|
||||
|
||||
rcl_ret_t
|
||||
rcl_lifecycle_trigger_transition_by_label(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
const char * label,
|
||||
bool publish_notification)
|
||||
{
|
||||
if (!state_machine) {
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "state machine pointer is null");
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
|
||||
const rcl_lifecycle_transition_t * transition =
|
||||
rcl_lifecycle_get_transition_by_label(state_machine->current_state, label);
|
||||
|
||||
return _trigger_transition(state_machine, transition, publish_notification);
|
||||
}
|
||||
|
||||
void
|
||||
rcl_print_state_machine(const rcl_lifecycle_state_machine_t * state_machine)
|
||||
|
@ -353,9 +400,8 @@ rcl_print_state_machine(const rcl_lifecycle_state_machine_t * state_machine)
|
|||
for (size_t j = 0; j < map->states[i].valid_transition_size; ++j) {
|
||||
RCUTILS_LOG_INFO_NAMED(
|
||||
ROS_PACKAGE_NAME,
|
||||
"\tNode %s: Key %d: Transition: %s",
|
||||
"\tNode %s: Transition: %s",
|
||||
map->states[i].label,
|
||||
map->states[i].valid_transition_keys[j],
|
||||
map->states[i].valid_transitions[j].label);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,51 +0,0 @@
|
|||
// Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||
//
|
||||
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||
// you may not use this file except in compliance with the License.
|
||||
// You may obtain a copy of the License at
|
||||
//
|
||||
// http://www.apache.org/licenses/LICENSE-2.0
|
||||
//
|
||||
// Unless required by applicable law or agreed to in writing, software
|
||||
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
|
||||
#ifndef STATES_H_
|
||||
#define STATES_H_
|
||||
|
||||
#include "rcl_lifecycle/data_types.h"
|
||||
#include "rcl_lifecycle/visibility_control.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
// primary states based on
|
||||
// design.ros2.org/articles/node_lifecycle.html
|
||||
extern rcl_lifecycle_state_t rcl_state_unknown;
|
||||
extern rcl_lifecycle_state_t rcl_state_unconfigured;
|
||||
extern rcl_lifecycle_state_t rcl_state_inactive;
|
||||
extern rcl_lifecycle_state_t rcl_state_active;
|
||||
extern rcl_lifecycle_state_t rcl_state_finalized;
|
||||
|
||||
extern rcl_lifecycle_state_t rcl_state_configuring;
|
||||
extern rcl_lifecycle_state_t rcl_state_cleaningup;
|
||||
extern rcl_lifecycle_state_t rcl_state_shuttingdown;
|
||||
extern rcl_lifecycle_state_t rcl_state_activating;
|
||||
extern rcl_lifecycle_state_t rcl_state_deactivating;
|
||||
extern rcl_lifecycle_state_t rcl_state_errorprocessing;
|
||||
|
||||
extern const rcl_lifecycle_transition_t rcl_transition_configure;
|
||||
extern const rcl_lifecycle_transition_t rcl_transition_cleanup;
|
||||
extern const rcl_lifecycle_transition_t rcl_transition_shutdown;
|
||||
extern const rcl_lifecycle_transition_t rcl_transition_activate;
|
||||
extern const rcl_lifecycle_transition_t rcl_transition_deactivate;
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif // extern "C"
|
||||
|
||||
#endif // STATES_H_
|
|
@ -55,11 +55,6 @@ rcl_lifecycle_transition_map_fini(
|
|||
{
|
||||
rcl_ret_t fcn_ret = RCL_RET_OK;
|
||||
|
||||
// for each state free the allocations for their keys/transitions
|
||||
for (unsigned int i = 0; i < transition_map->states_size; ++i) {
|
||||
allocator->deallocate(transition_map->states[i].valid_transition_keys, allocator->state);
|
||||
allocator->deallocate(transition_map->states[i].valid_transitions, allocator->state);
|
||||
}
|
||||
// free the primary states
|
||||
allocator->deallocate(transition_map->states, allocator->state);
|
||||
transition_map->states = NULL;
|
||||
|
@ -106,7 +101,6 @@ rcl_ret_t
|
|||
rcl_lifecycle_register_transition(
|
||||
rcl_lifecycle_transition_map_t * transition_map,
|
||||
rcl_lifecycle_transition_t transition,
|
||||
rcl_lifecycle_transition_key_t key,
|
||||
const rcutils_allocator_t * allocator)
|
||||
{
|
||||
RCUTILS_CHECK_ALLOCATOR_WITH_MSG(
|
||||
|
@ -135,7 +129,6 @@ rcl_lifecycle_register_transition(
|
|||
// finally set the new transition to the end of the array
|
||||
transition_map->transitions[transition_map->transitions_size - 1] = transition;
|
||||
|
||||
// connect transition to state key
|
||||
// we have to copy the transitons here once more to the actual state
|
||||
// as we can't assign only the pointer. This pointer gets invalidated whenever
|
||||
// we add a new transition and re-shuffle/re-allocate new memory for it.
|
||||
|
@ -152,20 +145,6 @@ rcl_lifecycle_register_transition(
|
|||
}
|
||||
state->valid_transitions = new_valid_transitions;
|
||||
|
||||
rcl_lifecycle_transition_key_t * new_valid_transition_keys = allocator->reallocate(
|
||||
state->valid_transition_keys,
|
||||
state->valid_transition_size * sizeof(rcl_lifecycle_transition_key_t),
|
||||
allocator->state);
|
||||
if (!new_valid_transitions) {
|
||||
RCL_SET_ERROR_MSG(
|
||||
"failed to reallocate memory for new transitions keys on state",
|
||||
rcl_get_default_allocator());
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
state->valid_transition_keys = new_valid_transition_keys;
|
||||
|
||||
// assign key
|
||||
state->valid_transition_keys[state->valid_transition_size - 1] = key;
|
||||
state->valid_transitions[state->valid_transition_size - 1] = transition;
|
||||
|
||||
return RCL_RET_OK;
|
||||
|
|
|
@ -28,8 +28,7 @@
|
|||
#include "rcutils/logging_macros.h"
|
||||
|
||||
#include "rcl_lifecycle/rcl_lifecycle.h"
|
||||
|
||||
#include "../src/default_state_machine.h"
|
||||
#include "rcl_lifecycle/default_state_machine.h"
|
||||
|
||||
class TestDefaultStateMachine : public ::testing::Test
|
||||
{
|
||||
|
@ -62,48 +61,47 @@ protected:
|
|||
}
|
||||
};
|
||||
|
||||
std::vector<rcl_lifecycle_transition_key_t> keys =
|
||||
{
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ACTIVATE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_DEACTIVATE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CLEANUP,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR
|
||||
};
|
||||
|
||||
void
|
||||
test_trigger_transition(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
int key,
|
||||
uint8_t key_id,
|
||||
unsigned int expected_current_state,
|
||||
unsigned int expected_goal_state)
|
||||
{
|
||||
EXPECT_EQ(
|
||||
expected_current_state, state_machine->current_state->id);
|
||||
EXPECT_EQ(
|
||||
RCL_RET_OK, rcl_lifecycle_trigger_transition(
|
||||
state_machine, key, false));
|
||||
RCL_RET_OK, rcl_lifecycle_trigger_transition_by_id(
|
||||
state_machine, key_id, false));
|
||||
EXPECT_EQ(
|
||||
expected_goal_state, state_machine->current_state->id);
|
||||
}
|
||||
|
||||
/*
|
||||
* Test suite
|
||||
*/
|
||||
TEST_F(TestDefaultStateMachine, zero_init) {
|
||||
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
|
||||
ASSERT_EQ(rcl_lifecycle_state_machine_is_initialized(&state_machine), RCL_RET_ERROR);
|
||||
EXPECT_EQ(rcl_lifecycle_state_machine_is_initialized(&state_machine), RCL_RET_ERROR);
|
||||
rcl_reset_error();
|
||||
const rcl_lifecycle_transition_map_t * transition_map = &state_machine.transition_map;
|
||||
ASSERT_EQ(transition_map->states_size, (unsigned int)0);
|
||||
ASSERT_EQ(transition_map->states, nullptr);
|
||||
ASSERT_EQ(transition_map->transitions_size, (unsigned int)0);
|
||||
ASSERT_EQ(transition_map->transitions, nullptr);
|
||||
EXPECT_EQ(transition_map->states_size, 0u);
|
||||
EXPECT_EQ(transition_map->states, nullptr);
|
||||
EXPECT_EQ(transition_map->transitions_size, 0u);
|
||||
EXPECT_EQ(transition_map->transitions, nullptr);
|
||||
|
||||
auto ret = rcl_lifecycle_state_machine_fini(&state_machine, this->node_ptr, this->allocator);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||
}
|
||||
|
||||
TEST_F(TestDefaultStateMachine, default_init) {
|
||||
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
|
||||
|
||||
auto ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
|
||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||
|
||||
ret = rcl_lifecycle_state_machine_fini(&state_machine, this->node_ptr, this->allocator);
|
||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||
}
|
||||
|
||||
TEST_F(TestDefaultStateMachine, default_sequence) {
|
||||
|
@ -121,7 +119,7 @@ TEST_F(TestDefaultStateMachine, default_sequence) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -133,7 +131,7 @@ TEST_F(TestDefaultStateMachine, default_sequence) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE);
|
||||
|
||||
|
@ -145,7 +143,7 @@ TEST_F(TestDefaultStateMachine, default_sequence) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -157,19 +155,19 @@ TEST_F(TestDefaultStateMachine, default_sequence) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_UNCONFIGURED_SHUTDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED);
|
||||
|
||||
|
@ -184,13 +182,39 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
|
||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||
|
||||
std::vector<uint8_t> transition_ids =
|
||||
{
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CLEANUP,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ACTIVATE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_DEACTIVATE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_ERROR,
|
||||
};
|
||||
|
||||
{ // supposed to stay unconfigured for all invalid
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN) {continue;}
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(
|
||||
state_machine.current_state->id,
|
||||
|
@ -205,12 +229,12 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR) {continue;}
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_ERROR) {continue;}
|
||||
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING);
|
||||
|
@ -220,18 +244,17 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
{ // supposed to stay inactive for all invalid
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_CLEANUP ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ACTIVATE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN) {continue;}
|
||||
|
||||
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "applying key %u", *it);
|
||||
EXPECT_EQ(
|
||||
RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
@ -245,12 +268,12 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR) {continue;}
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_ERROR) {continue;}
|
||||
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING);
|
||||
|
@ -260,16 +283,16 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
{ // supposed to stay active for all invalid
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_DEACTIVATE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN)
|
||||
{continue;}
|
||||
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE);
|
||||
|
@ -283,12 +306,12 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR) {continue;}
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_ERROR) {continue;}
|
||||
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING);
|
||||
|
@ -299,7 +322,7 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
// skip inactive, we tested that already
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
test_trigger_transition(
|
||||
|
@ -308,12 +331,12 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR) {continue;}
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_ERROR) {continue;}
|
||||
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP);
|
||||
|
@ -323,22 +346,22 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
{ // supposed to stay shutting down for all invalid
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
// shutdown directly, since we tested already unconfigured
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_UNCONFIGURED_SHUTDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR) {continue;}
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
if (*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_SUCCESS ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_FAILURE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_ERROR) {continue;}
|
||||
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN);
|
||||
|
@ -348,12 +371,12 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
{ // supposed to stay finalized for all invalid
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED);
|
||||
|
||||
for (auto it = keys.begin(); it != keys.end(); ++it) {
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
for (auto it = transition_ids.begin(); it != transition_ids.end(); ++it) {
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_lifecycle_trigger_transition_by_id(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(state_machine.current_state->id,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED);
|
||||
|
@ -380,7 +403,7 @@ TEST_F(TestDefaultStateMachine, default_in_a_loop) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -392,7 +415,7 @@ TEST_F(TestDefaultStateMachine, default_in_a_loop) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE);
|
||||
|
||||
|
@ -404,7 +427,7 @@ TEST_F(TestDefaultStateMachine, default_in_a_loop) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -416,20 +439,20 @@ TEST_F(TestDefaultStateMachine, default_in_a_loop) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
}
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_UNCONFIGURED_SHUTDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED);
|
||||
|
||||
|
@ -452,7 +475,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_FAILURE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
|
||||
|
@ -465,7 +488,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -477,7 +500,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_FAILURE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -490,7 +513,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE);
|
||||
test_trigger_transition(
|
||||
|
@ -501,7 +524,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_FAILURE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE);
|
||||
|
||||
|
@ -513,7 +536,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
test_trigger_transition(
|
||||
|
@ -523,7 +546,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_FAILURE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -535,17 +558,17 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
|
|||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_UNCONFIGURED_SHUTDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_FAILURE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED);
|
||||
|
||||
|
@ -568,13 +591,13 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
|
||||
|
@ -587,7 +610,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -599,13 +622,13 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
|
||||
|
@ -618,7 +641,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -630,7 +653,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE);
|
||||
|
||||
|
@ -641,13 +664,13 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
|
||||
|
@ -659,7 +682,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
test_trigger_transition(
|
||||
|
@ -669,30 +692,30 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
|
|||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
|
||||
/////////////////////////////
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_UNCONFIGURED_SHUTDOWN,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING);
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED);
|
||||
|
||||
|
@ -717,13 +740,13 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_unresolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_FAILURE,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_FAILURE,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED);
|
||||
|
||||
|
@ -745,7 +768,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_unresolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_SUCCESS,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE);
|
||||
|
||||
|
@ -757,14 +780,17 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_unresolved) {
|
|||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING);
|
||||
|
||||
test_trigger_transition(
|
||||
&state_machine,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_CALLBACK_ERROR,
|
||||
lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_ERROR,
|
||||
lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING,
|
||||
lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED);
|
||||
|
||||
EXPECT_EQ(RCL_RET_OK,
|
||||
rcl_lifecycle_state_machine_fini(&state_machine, this->node_ptr, this->allocator));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -26,8 +26,7 @@
|
|||
#include "rcl/rcl.h"
|
||||
|
||||
#include "rcl_lifecycle/rcl_lifecycle.h"
|
||||
|
||||
#include "../src/default_state_machine.h"
|
||||
#include "rcl_lifecycle/default_state_machine.h"
|
||||
|
||||
class TestMultipleInstances : public ::testing::Test
|
||||
{
|
||||
|
@ -62,15 +61,15 @@ protected:
|
|||
void
|
||||
test_trigger_transition(
|
||||
rcl_lifecycle_state_machine_t * state_machine,
|
||||
int key,
|
||||
uint8_t key_id,
|
||||
unsigned int expected_current_state,
|
||||
unsigned int expected_goal_state)
|
||||
{
|
||||
EXPECT_EQ(
|
||||
expected_current_state, state_machine->current_state->id);
|
||||
EXPECT_EQ(
|
||||
RCL_RET_OK, rcl_lifecycle_trigger_transition(
|
||||
state_machine, key, false));
|
||||
RCL_RET_OK, rcl_lifecycle_trigger_transition_by_id(
|
||||
state_machine, key_id, false));
|
||||
EXPECT_EQ(
|
||||
expected_goal_state, state_machine->current_state->id);
|
||||
}
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
|
||||
#include "rcl/error_handling.h"
|
||||
|
||||
#include "rcl_lifecycle/rcl_lifecycle.h"
|
||||
#include "rcl_lifecycle/transition_map.h"
|
||||
|
||||
class TestTransitionMap : public ::testing::Test
|
||||
|
@ -50,7 +51,7 @@ TEST_F(TestTransitionMap, initialized) {
|
|||
|
||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||
|
||||
rcl_lifecycle_state_t state0 = {"my_state", 0, NULL, NULL, 0};
|
||||
rcl_lifecycle_state_t state0 = {"my_state_0", 0, NULL, 0};
|
||||
rcl_ret_t ret = rcl_lifecycle_register_state(&transition_map, state0, &allocator);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_lifecycle_transition_map_is_initialized(&transition_map));
|
||||
|
@ -58,7 +59,7 @@ TEST_F(TestTransitionMap, initialized) {
|
|||
ret = rcl_lifecycle_register_state(&transition_map, state0, &allocator);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string_safe();
|
||||
|
||||
rcl_lifecycle_state_t state1 = {"my_state", 1, NULL, NULL, 0};
|
||||
rcl_lifecycle_state_t state1 = {"my_state_1", 1, NULL, 0};
|
||||
ret = rcl_lifecycle_register_state(&transition_map, state1, &allocator);
|
||||
|
||||
rcl_lifecycle_state_t * start_state =
|
||||
|
@ -71,7 +72,24 @@ TEST_F(TestTransitionMap, initialized) {
|
|||
rcl_lifecycle_transition_t transition01 = {"from0to1", 0,
|
||||
start_state, goal_state};
|
||||
ret = rcl_lifecycle_register_transition(
|
||||
&transition_map, transition01, 0, &allocator);
|
||||
&transition_map, transition01, &allocator);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
|
||||
rcl_lifecycle_transition_t transition10 = {"from1to0", 1,
|
||||
goal_state, start_state};
|
||||
ret = rcl_lifecycle_register_transition(
|
||||
&transition_map, transition10, &allocator);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
|
||||
const rcl_lifecycle_transition_t * trans =
|
||||
rcl_lifecycle_get_transition_by_id(start_state, 0);
|
||||
EXPECT_EQ(0u, trans->id);
|
||||
trans = rcl_lifecycle_get_transition_by_label(start_state, "from0to1");
|
||||
EXPECT_EQ(0u, trans->id);
|
||||
trans = rcl_lifecycle_get_transition_by_id(goal_state, 1);
|
||||
EXPECT_EQ(1u, trans->id);
|
||||
trans = rcl_lifecycle_get_transition_by_label(goal_state, "from1to0");
|
||||
EXPECT_EQ(1u, trans->id);
|
||||
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_lifecycle_transition_map_fini(&transition_map, &allocator));
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue