Fix class structure and virtual function
This commit is contained in:
@@ -59,7 +59,7 @@ class DrawingController(Node):
|
|||||||
self.timer = self.create_timer(timer_period, self.timer_callback)
|
self.timer = self.create_timer(timer_period, self.timer_callback)
|
||||||
self.i = 0
|
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):
|
while not self.cli.wait_for_service(timeout_sec=1.0):
|
||||||
self.get_logger().info('service not available, waiting again...')
|
self.get_logger().info('service not available, waiting again...')
|
||||||
self.req = ExecuteMotion.Request()
|
self.req = ExecuteMotion.Request()
|
||||||
|
|||||||
@@ -5,57 +5,35 @@
|
|||||||
class RobotController : public rclcpp::Node
|
class RobotController : public rclcpp::Node
|
||||||
{
|
{
|
||||||
public:
|
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>("execute_path", std::bind(&RobotController::executePath, this, std::placeholders::_1, std::placeholders::_2));
|
||||||
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();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//int (RobotController::*executePath)(const std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Request> request, std::shared_ptr<robot_interfaces::srv::ExecuteMotion::Response> response);
|
/// Callback that executes path on robot
|
||||||
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->path PoseStamped[]
|
||||||
//request->motion->acceleration float64
|
//request->motion->acceleration float64
|
||||||
//request->motion->velocity float64
|
//request->motion->velocity float64
|
||||||
RCLCPP_INFO(this->get_logger(), "NEW MOTION: Acceleration: ");
|
RCLCPP_INFO(this->get_logger(), "NEW MOTION: Acceleration: ");
|
||||||
//RCLCPP_INFO(this->get_logger(), "Acceleration: " + std::to_string(request.motion.acceleration));
|
//RCLCPP_INFO(this->get_logger(), "Acceleration: " + std::to_string(request.motion.acceleration));
|
||||||
response->status = "executePath not implemented";
|
response->status = "executePath not implemented";
|
||||||
RCLCPP_WARN(this->get_logger(), "executePath not implemented");
|
RCLCPP_WARN(this->get_logger(), "executePath not implemented");
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/// Callback that executes path on robot
|
|
||||||
|
|
||||||
rclcpp::Service<robot_interfaces::srv::ExecuteMotion>::SharedPtr service;
|
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.
|
// 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
|
class DummyController : public RobotController
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
||||||
DummyController(std::string name) : RobotController(name) {}
|
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->path PoseStamped[]
|
||||||
//request->motion->acceleration float64
|
//request->motion->acceleration float64
|
||||||
@@ -68,7 +46,6 @@ class DummyController : public RobotController
|
|||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
//RobotController::RobotController(name) : Node(name)
|
|
||||||
|
|
||||||
int main(int argc, char ** argv)
|
int main(int argc, char ** argv)
|
||||||
{
|
{
|
||||||
|
|||||||
Reference in New Issue
Block a user