Warn unused (#139)

* add unused warning

* comply with unused warning

* add unused warning

* comply with unused warning

* remove wrongly modified files

* consistent include style
This commit is contained in:
Karsten Knese 2017-05-25 19:52:25 -07:00 committed by GitHub
parent d433ee193c
commit 6fbfb4ee07
8 changed files with 61 additions and 19 deletions

View file

@ -30,6 +30,7 @@ rcl_lifecycle_state_machine_t
rcl_lifecycle_get_zero_initialized_state_machine();
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_lifecycle_state_machine_init(
rcl_lifecycle_state_machine_t * state_machine,
@ -42,17 +43,20 @@ rcl_lifecycle_state_machine_init(
bool default_states);
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_lifecycle_state_machine_fini(
rcl_lifecycle_state_machine_t * state_machine,
rcl_node_t * node_handle);
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_lifecycle_state_machine_is_initialized(
const rcl_lifecycle_state_machine_t * state_machine);
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
const rcl_lifecycle_transition_t *
rcl_lifecycle_is_valid_callback_transition(
rcl_lifecycle_state_machine_t * state_machine,
@ -70,6 +74,7 @@ rcl_lifecycle_is_valid_callback_transition(
* callbacks such as RCL_LIFECYCLE_RET_OK et. al.
*/
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_lifecycle_trigger_transition(
rcl_lifecycle_state_machine_t * state_machine,

View file

@ -16,6 +16,7 @@
#ifndef RCL_LIFECYCLE__TRANSITION_MAP_H_
#define RCL_LIFECYCLE__TRANSITION_MAP_H_
#include <rcl/macros.h>
#include <rcl_lifecycle/data_types.h>
#if __cplusplus
@ -37,12 +38,14 @@ rcl_lifecycle_register_transition(
rcl_lifecycle_ret_t key);
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
rcl_lifecycle_state_t *
rcl_lifecycle_get_state(
rcl_lifecycle_transition_map_t * transition_map,
unsigned int state_id);
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
rcl_lifecycle_transition_t *
rcl_lifecycle_get_transitions(
rcl_lifecycle_transition_map_t * transition_map,

View file

@ -22,18 +22,16 @@ extern "C"
#include <stdio.h>
#include <string.h>
#include "rcutils/concat.h"
#include <rcl/error_handling.h>
#include <rcutils/concat.h>
#include <rmw/validate_full_topic_name.h>
#include <rosidl_generator_c/message_type_support_struct.h>
#include <rosidl_generator_c/string_functions.h>
#include "lifecycle_msgs/msg/transition_event.h"
#include "rcl/error_handling.h"
#include <lifecycle_msgs/msg/transition_event.h>
#include "rcl_lifecycle/data_types.h"
#include "rmw/validate_full_topic_name.h"
#include "rosidl_generator_c/message_type_support_struct.h"
#include "rosidl_generator_c/string_functions.h"
static lifecycle_msgs__msg__TransitionEvent msg;
static const char * pub_transition_event_suffix = "transition_event";

View file

@ -20,12 +20,15 @@ extern "C"
{
#endif
#include <rcl/macros.h>
#include "rcl_lifecycle/data_types.h"
rcl_lifecycle_com_interface_t
rcl_lifecycle_get_zero_initialized_com_interface();
rcl_ret_t
RCL_WARN_UNUSED
rcl_lifecycle_com_interface_init(
rcl_lifecycle_com_interface_t * com_interface,
rcl_node_t * node_handle,
@ -36,11 +39,13 @@ rcl_lifecycle_com_interface_init(
const rosidl_service_type_support_t * ts_srv_get_available_transitions);
rcl_ret_t
RCL_WARN_UNUSED
rcl_lifecycle_com_interface_fini(
rcl_lifecycle_com_interface_t * com_interface,
rcl_node_t * node_handle);
rcl_ret_t
RCL_WARN_UNUSED
rcl_lifecycle_com_interface_publish_notification(
rcl_lifecycle_com_interface_t * com_interface,
const rcl_lifecycle_state_t * start, const rcl_lifecycle_state_t * goal);

View file

@ -15,6 +15,7 @@
#ifndef DEFAULT_STATE_MACHINE_H_
#define DEFAULT_STATE_MACHINE_H_
#include <rcl/macros.h>
#include <rcl/types.h>
#include "rcl_lifecycle/data_types.h"
@ -26,6 +27,7 @@ extern "C"
#endif
RCL_LIFECYCLE_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_lifecycle_init_default_state_machine(rcl_lifecycle_state_machine_t * state_machine);

View file

@ -165,8 +165,12 @@ rcl_lifecycle_trigger_transition(
}
state_machine->current_state = transition->goal;
if (publish_notification) {
rcl_lifecycle_com_interface_publish_notification(
rcl_ret_t ret = rcl_lifecycle_com_interface_publish_notification(
&state_machine->com_interface, transition->start, state_machine->current_state);
if (ret != RCL_RET_OK) {
RCL_SET_ERROR_MSG("Could not publish transition", rcl_get_default_allocator());
return RCL_RET_ERROR;
}
}
return RCL_RET_OK;

View file

@ -97,8 +97,11 @@ TEST_F(TestDefaultStateMachine, zero_init) {
}
TEST_F(TestDefaultStateMachine, default_sequence) {
rcl_ret_t ret;
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine);
ret = rcl_lifecycle_init_default_state_machine(&state_machine);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
test_trigger_transition(
&state_machine,
@ -162,8 +165,11 @@ TEST_F(TestDefaultStateMachine, default_sequence) {
}
TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
rcl_ret_t ret;
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine);
ret = rcl_lifecycle_init_default_state_machine(&state_machine);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
{ // supposed to stay unconfigured for all invalid
for (auto it = keys.begin(); it != keys.end(); ++it) {
@ -334,8 +340,11 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
}
TEST_F(TestDefaultStateMachine, default_in_a_loop) {
rcl_ret_t ret;
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine);
ret = rcl_lifecycle_init_default_state_machine(&state_machine);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
for (auto i = 0; i < 5; ++i) {
test_trigger_transition(
@ -401,8 +410,11 @@ TEST_F(TestDefaultStateMachine, default_in_a_loop) {
}
TEST_F(TestDefaultStateMachine, default_sequence_failure) {
rcl_ret_t ret;
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine);
ret = rcl_lifecycle_init_default_state_machine(&state_machine);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
test_trigger_transition(
&state_machine,
@ -511,8 +523,11 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
}
TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
rcl_ret_t ret;
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine);
ret = rcl_lifecycle_init_default_state_machine(&state_machine);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
test_trigger_transition(
&state_machine,
@ -652,10 +667,13 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
}
TEST_F(TestDefaultStateMachine, default_sequence_error_unresolved) {
rcl_ret_t ret;
{
rcl_lifecycle_state_machine_t state_machine =
rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine);
ret = rcl_lifecycle_init_default_state_machine(&state_machine);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
test_trigger_transition(
&state_machine,
@ -679,7 +697,8 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_unresolved) {
{
rcl_lifecycle_state_machine_t state_machine =
rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine);
ret = rcl_lifecycle_init_default_state_machine(&state_machine);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
test_trigger_transition(
&state_machine,

View file

@ -73,23 +73,29 @@ test_trigger_transition(
}
TEST_F(TestMultipleInstances, default_sequence_error_unresolved) {
rcl_ret_t ret;
rcl_lifecycle_state_machine_t state_machine1 =
rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine1);
ret = rcl_lifecycle_init_default_state_machine(&state_machine1);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
rcl_lifecycle_state_machine_t state_machine2 =
rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine2);
ret = rcl_lifecycle_init_default_state_machine(&state_machine2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
rcl_lifecycle_state_machine_t state_machine3 =
rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_init_default_state_machine(&state_machine3);
ret = rcl_lifecycle_init_default_state_machine(&state_machine3);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
test_trigger_transition(
&state_machine1,
lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE,
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING, state_machine1.current_state->id);