Skip to content

Commit 7d67208

Browse files
authored
Humble (#54)
* fix nav2_sms_behavior for humble * nav2_sms_behavior fix depend package * add CMAKELIST to sam bot * fix depend package * fixed curl package
1 parent ded0094 commit 7d67208

File tree

11 files changed

+50
-42
lines changed

11 files changed

+50
-42
lines changed
Lines changed: 14 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
cmake_minimum_required(VERSION 3.5)
2-
project(nav2_sms_recovery)
2+
project(nav2_sms_behavior)
33

44
# Default to C++14
55
set(CMAKE_CXX_STANDARD 14)
@@ -19,8 +19,11 @@ find_package(builtin_interfaces REQUIRED)
1919
find_package(tf2_ros REQUIRED)
2020
find_package(nav2_costmap_2d REQUIRED)
2121
find_package(nav2_core REQUIRED)
22-
find_package(nav2_recoveries REQUIRED)
22+
find_package(nav2_behaviors REQUIRED)
2323
find_package(pluginlib REQUIRED)
24+
find_package(rosidl_default_generators REQUIRED)
25+
find_package(action_msgs REQUIRED)
26+
find_package(CURL REQUIRED)
2427

2528
include_directories(
2629
include
@@ -43,16 +46,17 @@ set(dependencies
4346
nav2_costmap_2d
4447
nav2_core
4548
pluginlib
46-
nav2_recoveries
49+
nav2_behaviors
50+
CURL
4751
)
4852

4953
rosidl_generate_interfaces(${PROJECT_NAME}
50-
"action/SmsRecovery.action"
54+
"action/SendSms.action"
5155
DEPENDENCIES builtin_interfaces std_msgs
5256
)
5357

5458
add_library(${library_name} SHARED
55-
src/sms_recovery.cpp
59+
src/send_sms.cpp
5660
src/twilio.cpp
5761
)
5862

@@ -62,9 +66,11 @@ ament_target_dependencies(${library_name}
6266
${dependencies}
6367
)
6468

65-
rosidl_target_interfaces(${library_name} ${PROJECT_NAME} "rosidl_typesupport_cpp")
69+
rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
70+
target_link_libraries(${library_name} "${cpp_typesupport_target}")
6671

67-
pluginlib_export_plugin_description_file(nav2_core recovery_plugin.xml)
72+
73+
pluginlib_export_plugin_description_file(nav2_core behavior_plugin.xml)
6874

6975
install(TARGETS ${library_name}
7076
ARCHIVE DESTINATION lib
@@ -76,7 +82,7 @@ install(DIRECTORY include/
7682
DESTINATION include/
7783
)
7884

79-
install(FILES recovery_plugin.xml
85+
install(FILES behavior_plugin.xml
8086
DESTINATION share/${PROJECT_NAME}
8187
)
8288

File renamed without changes.
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
<library path="nav2_sms_behavior_plugin">
2+
<class name="nav2_sms_behavior/SendSms" type="nav2_sms_behavior::SendSms" base_class_type="nav2_core::Behavior">
3+
<description>This is an example plugin which produces an SMS text message behavior.</description>
4+
</class>
5+
</library>

nav2_sms_recovery/include/nav2_sms_recovery/sms_recovery.hpp renamed to nav2_sms_behavior/include/nav2_sms_behavior/send_sms.hpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -8,21 +8,21 @@
88
#include <string>
99
#include <memory>
1010

11-
#include "nav2_recoveries/recovery.hpp"
12-
#include "nav2_sms_recovery/action/sms_recovery.hpp"
13-
#include "nav2_sms_recovery/twilio.hpp"
11+
#include "nav2_behaviors/timed_behavior.hpp"
12+
#include "nav2_sms_behavior/action/send_sms.hpp"
13+
#include "nav2_sms_behavior/twilio.hpp"
1414

15-
namespace nav2_sms_recovery
15+
namespace nav2_sms_behavior
1616
{
1717

18-
using namespace nav2_recoveries; // NOLINT
19-
using Action = nav2_sms_recovery::action::SmsRecovery;
18+
using namespace nav2_behaviors; // NOLINT
19+
using Action = nav2_sms_behavior::action::SendSms;
2020

21-
class SMSRecovery : public Recovery<Action>
21+
class SendSms : public TimedBehavior<Action>
2222
{
2323
public:
24-
SMSRecovery();
25-
~SMSRecovery();
24+
SendSms();
25+
~SendSms();
2626

2727
Status onRun(const std::shared_ptr<const Action::Goal> command) override;
2828

nav2_sms_recovery/include/nav2_sms_recovery/twilio.hpp renamed to nav2_sms_behavior/include/nav2_sms_behavior/twilio.hpp

File renamed without changes.

nav2_sms_recovery/include/nav2_sms_recovery/type_conversion.hpp renamed to nav2_sms_behavior/include/nav2_sms_behavior/type_conversion.hpp

File renamed without changes.
Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
<?xml version="1.0"?>
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
4-
<name>nav2_sms_recovery</name>
4+
<name>nav2_sms_behavior</name>
55
<version>1.0.0</version>
6-
<description>Simple SMS recovery.</description>
6+
<description>Simple SMS send behavior.</description>
77
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
88
<license>MIT</license>
99

@@ -25,15 +25,17 @@
2525
<depend>builtin_interfaces</depend>
2626
<depend>tf2_ros</depend>
2727
<depend>nav2_costmap_2d</depend>
28-
<depend>nav2_recoveries</depend>
28+
<depend>nav2_behaviors</depend>
2929
<depend>nav2_core</depend>
3030
<depend>pluginlib</depend>
31+
<depend>action_msgs</depend>
32+
<depend>curl</depend>
3133

3234
<test_depend>ament_lint_auto</test_depend>
3335
<test_depend>ament_lint_common</test_depend>
3436

3537
<export>
3638
<build_type>ament_cmake</build_type>
37-
<nav2_core plugin="${prefix}/recovery_plugin.xml" />
39+
<nav2_core plugin="${prefix}/behavior_plugin.xml" />
3840
</export>
3941
</package>
Lines changed: 14 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -5,35 +5,35 @@
55
#include <chrono>
66
#include <memory>
77

8-
#include "nav2_sms_recovery/sms_recovery.hpp"
8+
#include "nav2_sms_behavior/send_sms.hpp"
99

10-
namespace nav2_sms_recovery
10+
namespace nav2_sms_behavior
1111
{
1212

13-
SMSRecovery::SMSRecovery()
14-
: Recovery<Action>()
13+
SendSms::SendSms()
14+
: TimedBehavior<Action>()
1515
{
1616
}
1717

18-
SMSRecovery::~SMSRecovery()
18+
SendSms::~SendSms()
1919
{
2020
}
2121

22-
void SMSRecovery::onConfigure()
22+
void SendSms::onConfigure()
2323
{
2424
auto node = node_.lock();
25-
node->declare_parameter("account_sid");
25+
node->declare_parameter("account_sid","");
2626
_account_sid = node->get_parameter("account_sid").as_string();
27-
node->declare_parameter("auth_token");
27+
node->declare_parameter("auth_token","");
2828
_auth_token = node->get_parameter("auth_token").as_string();
29-
node->declare_parameter("from_number");
29+
node->declare_parameter("from_number","");
3030
_from_number = node->get_parameter("from_number").as_string();
31-
node->declare_parameter("to_number");
31+
node->declare_parameter("to_number","");
3232
_to_number = node->get_parameter("to_number").as_string();
3333
_twilio = std::make_shared<twilio::Twilio>(_account_sid, _auth_token);
3434
}
3535

36-
Status SMSRecovery::onRun(const std::shared_ptr<const Action::Goal> command)
36+
Status SendSms::onRun(const std::shared_ptr<const Action::Goal> command)
3737
{
3838
auto node = node_.lock();
3939
std::string response;
@@ -44,7 +44,6 @@ Status SMSRecovery::onRun(const std::shared_ptr<const Action::Goal> command)
4444
response,
4545
"",
4646
false);
47-
4847
if (!message_success) {
4948
RCLCPP_INFO(node->get_logger(), "SMS send failed.");
5049
return Status::FAILED;
@@ -54,12 +53,12 @@ Status SMSRecovery::onRun(const std::shared_ptr<const Action::Goal> command)
5453
return Status::SUCCEEDED;
5554
}
5655

57-
Status SMSRecovery::onCycleUpdate()
56+
Status SendSms::onCycleUpdate()
5857
{
5958
return Status::SUCCEEDED;
6059
}
6160

62-
} // namespace nav2_sms_recovery
61+
} // namespace nav2_sms_behavior
6362

6463
#include "pluginlib/class_list_macros.hpp"
65-
PLUGINLIB_EXPORT_CLASS(nav2_sms_recovery::SMSRecovery, nav2_core::Recovery)
64+
PLUGINLIB_EXPORT_CLASS(nav2_sms_behavior::SendSms, nav2_core::Behavior)
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
#include <sstream>
55
#include <curl/curl.h>
66

7-
#include "nav2_sms_recovery/twilio.hpp"
7+
#include "nav2_sms_behavior/twilio.hpp"
88

99

1010
namespace twilio {

nav2_sms_recovery/recovery_plugin.xml

Lines changed: 0 additions & 5 deletions
This file was deleted.

0 commit comments

Comments
 (0)