ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Hey, the basis of all your robot movements will be ros_control, a very generic ROS framework for controlling actuators. If you already have your robot working in gazebo, you are probably aware of the way ros_control
interacts with gazebo (see this tutorial for more information). Based on this, there are several levels where you could start integrating a custom FK/IK:
effort_controllers/JointGroupPositionController
), which just listens for an array of target joint positions on a command
topic and tries to move there with little PID logic. You would then wrap your IK inside a custom node, which would listen for cartesian targets and then send joint configuration targets to the controller.ros_control
knowledge, you could use both your IK and your FK to implement a custom ros_control
controller, which would then directly directly run in the robot control loop. Examples for this approach can be found in the cartesian_controllers package.ros_control
"under the hood" to send commands to actuators (and get feedback from them).Some general remarks: I think if your main goal is to learn about FK/IK implementation, stick with 1 and 2. You won't get around learning a bit of how ros_control
works, as this is the basis of most actuation in ROS (and the control methodology used in Gazebo), but this should be manageable. There are some great tutorials out there, in addition i would just recommend taking a look at rqt_controller_manager when you get to fiddling around with your simulation.
Your IK will be much more useful then your FK in most cases, as ROS typically uses robot_state_publisher for all its FK needs. If you can already see your gazebo robot in rviz, you probably already have this running. The typical FK pipeline in ROS looks something like:
ros_control
has a joint_state_controller
running, which publishes all joint states on the joint_states
topic.robot_state_publisher
reads your robot_description
from your URDF files and listens to joint_states
, calculating the position of all links based on its forward kinematics and publishing it as tf
transforms.robot_description
and renders them at the poses it gets from tf
This does of course not mean that implementing a custom FK doesn't have any use cases, there are for example some parallel kinematics that cannot be described reasonably in the URDF format (mostly weird parallel kinematics). But i hope this gives you a broad "thousand feet above" overview about the topics you touched, feel free to ask more about specifics.