parent
e41661ca61
commit
15e172d066
@ -37,7 +37,8 @@ add_executable(ros2aria
|
|||||||
src/sonar.cpp
|
src/sonar.cpp
|
||||||
src/pose.cpp
|
src/pose.cpp
|
||||||
src/gripper.cpp
|
src/gripper.cpp
|
||||||
src/wheels.cpp)
|
src/wheels.cpp
|
||||||
|
src/clutch.cpp)
|
||||||
|
|
||||||
ament_target_dependencies(ros2aria rclcpp)
|
ament_target_dependencies(ros2aria rclcpp)
|
||||||
ament_target_dependencies(ros2aria std_srvs)
|
ament_target_dependencies(ros2aria std_srvs)
|
||||||
|
12
src/ros2aria/src/clutch.cpp
Normal file
12
src/ros2aria/src/clutch.cpp
Normal file
@ -0,0 +1,12 @@
|
|||||||
|
#include "ros2aria.hpp"
|
||||||
|
|
||||||
|
void Ros2Aria::clutch_callback(const std_msgs::msg::Bool::SharedPtr msg)
|
||||||
|
{
|
||||||
|
std::lock_guard<RAIIBot> lock(*robot.get());
|
||||||
|
|
||||||
|
auto r = robot->getRobot();
|
||||||
|
if (msg->data)
|
||||||
|
r->enableMotors();
|
||||||
|
else
|
||||||
|
r->disableMotors();
|
||||||
|
}
|
@ -12,6 +12,8 @@ Ros2Aria::Ros2Aria()
|
|||||||
RCLCPP_INFO(this->get_logger(), "starting subscribers and services");
|
RCLCPP_INFO(this->get_logger(), "starting subscribers and services");
|
||||||
cmd_vel_sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
|
cmd_vel_sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
|
||||||
"cmd_vel", 10, std::bind(&Ros2Aria::cmd_vel_callback, this, _1));
|
"cmd_vel", 10, std::bind(&Ros2Aria::cmd_vel_callback, this, _1));
|
||||||
|
clutch_sub_ = this->create_subscription<std_msgs::msg::Bool>(
|
||||||
|
"clutch", 10, std::bind(&Ros2Aria::clutch_callback, this, _1));
|
||||||
|
|
||||||
sonar_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud>("sonar", 10);
|
sonar_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud>("sonar", 10);
|
||||||
sonar_pointcloud2_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("sonar_pointcloud2", 10);
|
sonar_pointcloud2_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("sonar_pointcloud2", 10);
|
||||||
|
@ -7,6 +7,7 @@
|
|||||||
#include "geometry_msgs/msg/twist.hpp"
|
#include "geometry_msgs/msg/twist.hpp"
|
||||||
#include "nav_msgs/msg/odometry.hpp"
|
#include "nav_msgs/msg/odometry.hpp"
|
||||||
#include "std_srvs/srv/empty.hpp"
|
#include "std_srvs/srv/empty.hpp"
|
||||||
|
#include "std_msgs/msg/bool.hpp"
|
||||||
|
|
||||||
#include "./raiibot.cpp"
|
#include "./raiibot.cpp"
|
||||||
|
|
||||||
@ -47,6 +48,9 @@ private:
|
|||||||
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;
|
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;
|
||||||
void cmd_vel_callback(const geometry_msgs::msg::Twist::SharedPtr msg);
|
void cmd_vel_callback(const geometry_msgs::msg::Twist::SharedPtr msg);
|
||||||
|
|
||||||
|
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr clutch_sub_;
|
||||||
|
void clutch_callback(const std_msgs::msg::Bool::SharedPtr msg);
|
||||||
|
|
||||||
// services
|
// services
|
||||||
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr stop_service_;
|
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr stop_service_;
|
||||||
void stop(const std::shared_ptr<std_srvs::srv::Empty::Request> request, std::shared_ptr<std_srvs::srv::Empty::Response> response) const;
|
void stop(const std::shared_ptr<std_srvs::srv::Empty::Request> request, std::shared_ptr<std_srvs::srv::Empty::Response> response) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user