Skip to content

Commit

Permalink
Now using active verbs as described in the design doc:
Browse files Browse the repository at this point in the history
  • Loading branch information
jacobperron committed Mar 30, 2019
1 parent 54a8b18 commit 9958990
Show file tree
Hide file tree
Showing 6 changed files with 13 additions and 13 deletions.
4 changes: 2 additions & 2 deletions rclcpp/minimal_action_server/not_composable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void execute(
if (goal_handle->is_canceling())
{
result->sequence = sequence;
goal_handle->set_canceled(result);
goal_handle->cancel(result);
RCLCPP_INFO(rclcpp::get_logger("server"), "Goal Canceled");
return;
}
Expand All @@ -77,7 +77,7 @@ void execute(
// Check if goal is done
if (rclcpp::ok()) {
result->sequence = sequence;
goal_handle->set_succeeded(result);
goal_handle->succeed(result);
RCLCPP_INFO(rclcpp::get_logger("server"), "Goal Suceeded");
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ async def execute_callback(self, goal_handle):
# Start executing the action
for i in range(1, goal_handle.request.order):
if goal_handle.is_cancel_requested:
goal_handle.set_canceled()
goal_handle.cancel()
self.get_logger().info('Goal canceled')
return Fibonacci.Result()

Expand All @@ -78,7 +78,7 @@ async def execute_callback(self, goal_handle):
# Sleep for demonstration purposes
time.sleep(1)

goal_handle.set_succeeded()
goal_handle.succeed()

# Populate result message
result = Fibonacci.Result()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ async def execute_callback(self, goal_handle):
# Start executing the action
for i in range(1, goal_handle.request.order):
if goal_handle.is_cancel_requested:
goal_handle.set_canceled()
goal_handle.cancel()
self.get_logger().info('Goal canceled')
return Fibonacci.Result()

Expand All @@ -92,7 +92,7 @@ async def execute_callback(self, goal_handle):
# Sleep for demonstration purposes
time.sleep(1)

goal_handle.set_succeeded()
goal_handle.succeed()

# Populate result message
result = Fibonacci.Result()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ async def execute_callback(goal_handle):
# Start executing the action
for i in range(1, goal_handle.request.order):
if goal_handle.is_cancel_requested:
goal_handle.set_canceled()
goal_handle.cancel()
logger.info('Goal canceled')
return Fibonacci.Result()

Expand All @@ -57,7 +57,7 @@ async def execute_callback(goal_handle):
# Sleep for demonstration purposes
time.sleep(1)

goal_handle.set_succeeded()
goal_handle.succeed()

# Populate result message
result = Fibonacci.Result()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ def execute_callback(self, goal_handle):
# Start executing the action
for i in range(1, goal_handle.request.order):
if goal_handle.is_cancel_requested:
goal_handle.set_canceled()
goal_handle.cancel()
self.get_logger().info('Goal canceled')
return Fibonacci.Result()

Expand All @@ -74,7 +74,7 @@ def execute_callback(self, goal_handle):
# Sleep for demonstration purposes
time.sleep(1)

goal_handle.set_succeeded()
goal_handle.succeed()

# Populate result message
result = Fibonacci.Result()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ def handle_accepted_callback(self, goal_handle):
if self._goal_handle is not None and self._goal_handle.is_active:
self.get_logger().info('Aborting previous goal')
# Abort the existing goal
self._goal_handle.set_aborted()
self._goal_handle.abort()
self._goal_handle = goal_handle

goal_handle.execute()
Expand All @@ -83,7 +83,7 @@ def execute_callback(self, goal_handle):
return Fibonacci.Result()

if goal_handle.is_cancel_requested:
goal_handle.set_canceled()
goal_handle.cancel()
self.get_logger().info('Goal canceled')
return Fibonacci.Result()

Expand All @@ -98,7 +98,7 @@ def execute_callback(self, goal_handle):
# Sleep for demonstration purposes
time.sleep(1)

goal_handle.set_succeeded()
goal_handle.succeed()

# Populate result message
result = Fibonacci.Result()
Expand Down

0 comments on commit 9958990

Please sign in to comment.