add a simple node

This commit is contained in:
Wojciech Kwolek 2021-03-19 15:09:56 +00:00
parent 15536ba2d8
commit 1bb7b6a17d
3 changed files with 58 additions and 11 deletions

View File

@ -17,17 +17,22 @@ endif()
# find dependencies # find dependencies
find_package(ament_cmake REQUIRED) find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_srvs REQUIRED)
# uncomment the following section in order to fill in # uncomment the following section in order to fill in
# further dependencies manually. # further dependencies manually.
# find_package(<dependency> REQUIRED) # find_package(<dependency> REQUIRED)
add_executable(ros2aria src/ros2aria.cpp) add_executable(ros2aria src/ros2aria.cpp)
ament_target_dependencies(ros2aria rclcpp)
ament_target_dependencies(ros2aria std_srvs)
target_include_directories(ros2aria PUBLIC target_include_directories(ros2aria PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include> $<INSTALL_INTERFACE:include>
/usr/local/Aria/include) /usr/local/Aria/include)
target_link_libraries(ros2aria /usr/local/Aria/lib/libAria.so) target_link_libraries(ros2aria /usr/local/Aria/lib/libAria.so)
install(TARGETS ros2aria install(TARGETS ros2aria

View File

@ -12,6 +12,9 @@
<test_depend>ament_lint_auto</test_depend> <test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend> <test_depend>ament_lint_common</test_depend>
<depend>rclcpp</depend>
<depend>std_srvs</depend>
<export> <export>
<build_type>ament_cmake</build_type> <build_type>ament_cmake</build_type>
</export> </export>

View File

@ -1,7 +1,41 @@
#include <cstdio> #include <cstdio>
#include <memory>
#include "Aria/Aria.h" #include "Aria/Aria.h"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_srvs/srv/empty.hpp"
using std::placeholders::_1;
using std::placeholders::_2;
class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber()
: Node("minimal_subscriber")
{
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
service_ = this->create_service<std_srvs::srv::Empty>("stop", std::bind(&MinimalSubscriber::stop, this, _1, _2));
}
private:
void topic_callback(const std_msgs::msg::String::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
private:
void stop(const std::shared_ptr<std_srvs::srv::Empty::Request> request, std::shared_ptr<std_srvs::srv::Empty::Response> response) const
{
RCLCPP_INFO(this->get_logger(), "stop");
rclcpp::shutdown();
}
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr service_;
};
int main(int argc, char **argv) int main(int argc, char **argv)
{ {
(void)argc; (void)argc;
@ -16,9 +50,9 @@ int main(int argc, char **argv)
args->add("-robotPort /dev/ttyS0"); // pass robot's serial port to Aria args->add("-robotPort /dev/ttyS0"); // pass robot's serial port to Aria
// args->add("-robotLogPacketsReceived"); // log received packets // args->add("-robotLogPacketsReceived"); // log received packets
// args->add("-robotLogPacketsSent"); // log sent packets // args->add("-robotLogPacketsSent"); // log sent packets
args->add("-robotLogVelocitiesReceived"); // log received velocities // args->add("-robotLogVelocitiesReceived"); // log received velocities
args->add("-robotLogMovementSent"); // args->add("-robotLogMovementSent");
args->add("-robotLogMovementReceived"); // args->add("-robotLogMovementReceived");
ArRobotConnector *conn = new ArRobotConnector(argparser, robot); // warning never freed ArRobotConnector *conn = new ArRobotConnector(argparser, robot); // warning never freed
if (!conn->connectRobot()) if (!conn->connectRobot())
{ {
@ -30,17 +64,22 @@ int main(int argc, char **argv)
printf("Enabling motors\n"); printf("Enabling motors\n");
robot->enableMotors(); robot->enableMotors();
printf("Enabled motors\n"); // printf("Enabled motors\n");
robot->setVel(2); // robot->setVel(2);
robot->move(500); // robot->move(500);
sleep(10); // sleep(10);
robot->move(-500); // robot->move(-500);
sleep(2); // sleep(2);
conn->disconnectAll(); // conn->disconnectAll();
return 0; // return 0;
// return 0;
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0; return 0;
} }