Fix class structure and virtual function

This commit is contained in:
2022-12-20 08:59:08 +02:00
parent 3b56bac43e
commit d843c422ef
2 changed files with 15 additions and 38 deletions

View File

@@ -59,7 +59,7 @@ class DrawingController(Node):
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
self.cli = self.create_client(ExecuteMotion, 'dummy_execute_path')
self.cli = self.create_client(ExecuteMotion, 'execute_path')
while not self.cli.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.req = ExecuteMotion.Request()

View File

@@ -5,31 +5,13 @@
class RobotController : public rclcpp::Node
{
public:
/// Constructor
RobotController(std::string name)
: Node(name)
RobotController(std::string name) : Node(name)
{
//this->service = this->create_service<robot_interfaces::srv::ExecuteMotion>(name+"_execute_path", &this->executePath);
this->service = this->create_service<robot_interfaces::srv::ExecuteMotion>(name+"_execute_path", std::bind(&RobotController::executePath, this, std::placeholders::_1, std::placeholders::_2));
// Subscribe to target pose
//target_pose_sub_ = this->create_subscription<geometry_msgs::msg::PoseStamped>("/target_pose", rclcpp::QoS(1), std::bind(&MoveItFollowTarget::target_pose_callback, this, std::placeholders::_1));
//RCLCPP_INFO(this->get_logger(), "Initialization successful.");
//std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_server");
//rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service = node->create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", &add);
//RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");
//rclcpp::spin(node);
//rclcpp::shutdown();
this->service = this->create_service<robot_interfaces::srv::ExecuteMotion>("execute_path", std::bind(&RobotController::executePath, this, std::placeholders::_1, std::placeholders::_2));
}
//int (RobotController::*executePath)(const std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Request> request, std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Response> response);
void executePath(const std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Request> request, std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Response> response) const
/// Callback that executes path on robot
virtual void executePath(const std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Request> request, std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Response> response)
{
//request->motion->path PoseStamped[]
//request->motion->acceleration float64
@@ -41,21 +23,17 @@ void executePath(const std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Req
}
private:
/// Callback that executes path on robot
rclcpp::Service<robot_interfaces::srv::ExecuteMotion>::SharedPtr service;
};
// A controller for a Dummy robot. Only logs messages and serves as an example for real implementation.
// CRTP pattern used here https://en.wikipedia.org/wiki/Curiously_recurring_template_pattern
//class DummyController : public RobotController<DummyController>
class DummyController : public RobotController
{
public:
DummyController(std::string name) : RobotController(name) {}
void executePath(const std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Request> request, std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Response> response) const
virtual void executePath(const std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Request> request, std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Response> response)
{
//request->motion->path PoseStamped[]
//request->motion->acceleration float64
@@ -68,7 +46,6 @@ class DummyController : public RobotController
};
//RobotController::RobotController(name) : Node(name)
int main(int argc, char ** argv)
{