Compare commits
No commits in common. "50767ebc272b6601051471f415b4617fbdfc3b24" and "d120d122a4afbb22071dcabf83d3ef30b5365084" have entirely different histories.
50767ebc27
...
d120d122a4
5
.vscode/settings.json
vendored
5
.vscode/settings.json
vendored
@ -1,8 +1,5 @@
|
||||
{
|
||||
"python.autoComplete.extraPaths": [
|
||||
"/opt/ros/foxy/lib/python3.8/site-packages"
|
||||
],
|
||||
"files.associations": {
|
||||
"functional": "cpp"
|
||||
}
|
||||
]
|
||||
}
|
@ -19,7 +19,6 @@ endif()
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(rclcpp REQUIRED)
|
||||
find_package(std_srvs REQUIRED)
|
||||
find_package(geometry_msgs REQUIRED)
|
||||
# uncomment the following section in order to fill in
|
||||
# further dependencies manually.
|
||||
# find_package(<dependency> REQUIRED)
|
||||
@ -28,7 +27,6 @@ find_package(geometry_msgs REQUIRED)
|
||||
add_executable(ros2aria src/ros2aria.cpp)
|
||||
ament_target_dependencies(ros2aria rclcpp)
|
||||
ament_target_dependencies(ros2aria std_srvs)
|
||||
ament_target_dependencies(ros2aria geometry_msgs)
|
||||
target_include_directories(ros2aria PUBLIC
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||
$<INSTALL_INTERFACE:include>
|
||||
|
@ -14,7 +14,6 @@
|
||||
|
||||
<depend>rclcpp</depend>
|
||||
<depend>std_srvs</depend>
|
||||
<depend>geometry_msgs</depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
|
@ -6,8 +6,6 @@
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "std_msgs/msg/string.hpp"
|
||||
#include "std_srvs/srv/empty.hpp"
|
||||
#include "geometry_msgs/msg/twist.hpp"
|
||||
|
||||
using std::placeholders::_1;
|
||||
using std::placeholders::_2;
|
||||
|
||||
@ -37,30 +35,20 @@ public:
|
||||
this->robot->runAsync(true);
|
||||
this->robot->enableMotors();
|
||||
|
||||
cmd_vel_sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
|
||||
"cmd_vel", 10, std::bind(&MinimalSubscriber::cmd_vel_callback, this, _1));
|
||||
stop_service_ = this->create_service<std_srvs::srv::Empty>("stop", std::bind(&MinimalSubscriber::stop, this, _1, _2));
|
||||
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:
|
||||
ArRobot *robot;
|
||||
ArRobotConnector *robotConn;
|
||||
|
||||
void cmd_vel_callback(const geometry_msgs::msg::Twist::SharedPtr msg) const
|
||||
void topic_callback(const std_msgs::msg::String::SharedPtr msg) const
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "cmd_vel: %f", msg->linear.x);
|
||||
float x, y, z;
|
||||
x = msg->linear.x;
|
||||
y = msg->linear.y;
|
||||
z = msg->angular.z;
|
||||
this->robot->lock();
|
||||
this->robot->setVel(x * 1e3);
|
||||
if (robot->hasLatVel())
|
||||
robot->setLatVel(y * 1e3);
|
||||
robot->setRotVel(z * 180 / M_PI);
|
||||
robot->unlock();
|
||||
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
|
||||
}
|
||||
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;
|
||||
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
|
||||
|
||||
void stop(const std::shared_ptr<std_srvs::srv::Empty::Request> request, std::shared_ptr<std_srvs::srv::Empty::Response> response) const
|
||||
{
|
||||
@ -68,7 +56,7 @@ private:
|
||||
this->robotConn->disconnectAll();
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr stop_service_;
|
||||
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr service_;
|
||||
};
|
||||
|
||||
int main(int argc, char **argv)
|
||||
|
Loading…
Reference in New Issue
Block a user