@@ -73,49 +73,47 @@ inline BT::NodeStatus GoalUpdater::tick()
73
73
if (last_goal_received_set_) {
74
74
if (last_goal_received_.header .stamp == rclcpp::Time (0 )) {
75
75
// if the goal doesn't have a timestamp, we reject it
76
- RCLCPP_WARN (
76
+ RCLCPP_WARN (
77
77
node_->get_logger (), " The received goal has no timestamp. Ignoring." );
78
- setOutput (" output_goal" , goal);
78
+ setOutput (" output_goal" , goal);
79
+ } else {
80
+ auto last_goal_received_time = rclcpp::Time (last_goal_received_.header .stamp );
81
+ auto goal_time = rclcpp::Time (goal.header .stamp );
82
+ if (last_goal_received_time >= goal_time) {
83
+ setOutput (" output_goal" , last_goal_received_);
79
84
} else {
80
- auto last_goal_received_time = rclcpp::Time (last_goal_received_.header .stamp );
81
- auto goal_time = rclcpp::Time (goal.header .stamp );
82
- if (last_goal_received_time >= goal_time) {
83
- setOutput (" output_goal" , last_goal_received_);
84
- } else {
85
- RCLCPP_WARN (
85
+ RCLCPP_WARN (
86
86
node_->get_logger (), " The timestamp of the received goal (%f) is older than the "
87
87
" current goal (%f). Ignoring the received goal." ,
88
88
last_goal_received_time.seconds (), goal_time.seconds ());
89
- setOutput (" output_goal" , goal);
90
- }
89
+ setOutput (" output_goal" , goal);
91
90
}
92
- }
93
- else {
91
+ }
92
+ } else {
94
93
setOutput (" output_goal" , goal);
95
94
}
96
95
97
96
if (last_goals_received_set_) {
98
97
if (last_goals_received_.poses .empty ()) {
99
- setOutput (" output_goals" , goals);
100
- } else if (last_goals_received_.header .stamp == rclcpp::Time (0 )) {
101
- RCLCPP_WARN (
98
+ setOutput (" output_goals" , goals);
99
+ } else if (last_goals_received_.header .stamp == rclcpp::Time (0 )) {
100
+ RCLCPP_WARN (
102
101
node_->get_logger (), " The received goals array has no timestamp. Ignoring." );
103
- setOutput (" output_goals" , goals);
102
+ setOutput (" output_goals" , goals);
103
+ } else {
104
+ auto last_goals_received_time = rclcpp::Time (last_goals_received_.header .stamp );
105
+ auto goals_time = rclcpp::Time (goals.header .stamp );
106
+ if (last_goals_received_time >= goals_time) {
107
+ setOutput (" output_goals" , last_goals_received_);
104
108
} else {
105
- auto last_goals_received_time = rclcpp::Time (last_goals_received_.header .stamp );
106
- auto goals_time = rclcpp::Time (goals.header .stamp );
107
- if (last_goals_received_time >= goals_time) {
108
- setOutput (" output_goals" , last_goals_received_);
109
- } else {
110
- RCLCPP_WARN (
109
+ RCLCPP_WARN (
111
110
node_->get_logger (), " The timestamp of the received goals (%f) is older than the "
112
111
" current goals (%f). Ignoring the received goals." ,
113
112
last_goals_received_time.seconds (), goals_time.seconds ());
114
- setOutput (" output_goals" , goals);
115
- }
113
+ setOutput (" output_goals" , goals);
116
114
}
117
- }
118
- else {
115
+ }
116
+ } else {
119
117
setOutput (" output_goals" , goals);
120
118
}
121
119
0 commit comments