40 #include <moveit_msgs/srv/get_position_ik.hpp>
41 #include <moveit_msgs/srv/get_position_fk.hpp>
53 bool computeIKService(
const std::shared_ptr<rmw_request_id_t>& request_header,
54 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
55 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res);
56 bool computeFKService(
const std::shared_ptr<rmw_request_id_t>& request_header,
57 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
58 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res);
60 void computeIK(moveit_msgs::msg::PositionIKRequest& req, moveit_msgs::msg::RobotState& solution,
65 rclcpp::Service<moveit_msgs::srv::GetPositionFK>::SharedPtr fk_service_;
66 rclcpp::Service<moveit_msgs::srv::GetPositionIK>::SharedPtr ik_service_;
void initialize() override
MoveGroupKinematicsService()
Representation of a robot's state. This includes position, velocity, acceleration and effort.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...