File tree Expand file tree Collapse file tree 3 files changed +14
-7
lines changed
include/nav2_sms_behavior Expand file tree Collapse file tree 3 files changed +14
-7
lines changed Original file line number Diff line number Diff line change @@ -3,5 +3,6 @@ string message
33---
44#result definition
55builtin_interfaces/Duration total_elapsed_time
6+ uint16 error_code
67---
78#feedback definition
Original file line number Diff line number Diff line change @@ -24,12 +24,18 @@ class SendSms : public TimedBehavior<Action>
2424 SendSms ();
2525 ~SendSms ();
2626
27- Status onRun (const std::shared_ptr<const Action::Goal> command) override ;
27+ ResultStatus onRun (const std::shared_ptr<const Action::Goal> command) override ;
2828
29- Status onCycleUpdate () override ;
29+ ResultStatus onCycleUpdate () override ;
3030
3131 void onConfigure () override ;
3232
33+ /* *
34+ * @brief Method to determine the required costmap info
35+ * @return costmap resources needed
36+ */
37+ nav2_core::CostmapInfoType getResourceInfo () override {return nav2_core::CostmapInfoType::NONE;}
38+
3339protected:
3440 std::string _account_sid;
3541 std::string _auth_token;
Original file line number Diff line number Diff line change @@ -33,7 +33,7 @@ void SendSms::onConfigure()
3333 _twilio = std::make_shared<twilio::Twilio>(_account_sid, _auth_token);
3434}
3535
36- Status SendSms::onRun (const std::shared_ptr<const Action::Goal> command)
36+ ResultStatus SendSms::onRun (const std::shared_ptr<const Action::Goal> command)
3737{
3838 auto node = node_.lock ();
3939 std::string response;
@@ -46,16 +46,16 @@ Status SendSms::onRun(const std::shared_ptr<const Action::Goal> command)
4646 false );
4747 if (!message_success) {
4848 RCLCPP_INFO (node->get_logger (), " SMS send failed." );
49- return Status::FAILED;
49+ return ResultStatus{ Status::FAILED} ;
5050 }
5151
5252 RCLCPP_INFO (node->get_logger (), " SMS sent successfully!" );
53- return Status::SUCCEEDED;
53+ return ResultStatus{ Status::SUCCEEDED} ;
5454}
5555
56- Status SendSms::onCycleUpdate ()
56+ ResultStatus SendSms::onCycleUpdate ()
5757{
58- return Status::SUCCEEDED;
58+ return ResultStatus{ Status::SUCCEEDED} ;
5959}
6060
6161} // namespace nav2_sms_behavior
You can’t perform that action at this time.
0 commit comments