ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders

To start (and this is slightly pedantic), but joint_state_controller (JSC) does not read from your robot's encoders. It retrieves joint state through something called a JointStateInterface and this state is comprised of position, velocity and effort.

The "only" task of the JSC is to take that state, convert it into a sensor_msgs/JointState message and publish it.

As this "controller" (and I place this in quotes as it doesn't really control anything, but that's just ros_control nomenclature) has to do that in a generic way (ie: it cannot know anything about any robot's specific implementation, or we could not all reuse the same JSC), hiding such details as "ticks" and "encoders" from the JSC (and other controllers in ros_control) is the task of the hardware_interface.

This piece of the ros_control stack is the interface to the hardware, and it performs a number of functions:

  1. it takes are of converting whatever units the robot hw uses into ROS standard units (REP-103)
  2. it provides a way to communicate with the hw (ie: using a serial bus, a fieldbus (ethercat, canbus, powerlink, profinet, profibus, ..), plain ethernet, TCP or UDP sockets, GPIO, direct memory registers, etc, etc)
  3. it takes care of any special initialisation routines or procedures that are needed to put the hardware in a state where it can actually be controlled
  4. it deals with error handling and recovery

And most (all?) of this is intended to abstract away implementation details about the robot for one purpose: if we hide all (most) knowledge of the actual hardware being used/addressed behind the hardware_interface, we can reuse as much of ros_control as possible, as none of the controllers (for instance) need to know anything about "encoders", "ticks" or any such things. This is the main idea behind ros_control (and in fact all of software engineering where abstraction is used to hide "implementation details" as they are called).

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders, are they ticks, ticks per meter or rad?

I hope you already know the answer to this now, but just to make it clear: they are not ticks, but the units that we've standardised on in ROS. So:

  • position: radians or metres (for revolute and prismatic joints respectively)
  • velocity: radians/sec or metres/sec (idem)
  • effort: Newtons or Newton metres (idem)

The hardware_interface will have to already have performed the conversion.

and if it was ticks, where can I provide the Radius of the wheels to the Controller?

I hope this one is already clear now as well: the controller does not do any conversion of units, so it does not need to know about ticks or wheel radii.

If you're thinking about odometry, then keep in mind that there are two levels of sensor data processing here: first from hw specific units to ROS units (reponsibility of the hardware_interface) and second from joint state to vehicle state.

In ros_control, for wheeled platforms, the latter is typically done by something like the diff_drive_controller. It is that controller that must know something about wheel radii, as it has to convert joint velocities into vehicle velocities and vice versa (ie: state and setpoints).

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders

To start (and this is slightly pedantic), but joint_state_controller (JSC) does not read from your robot's encoders. It retrieves joint state through something called a JointStateInterface and this state is comprised of position, velocity and effort.

The "only" task of the JSC is to take that state, convert it into a sensor_msgs/JointState message and publish it.

As this "controller" (and I place this in quotes as it doesn't really control anything, but that's just ros_control nomenclature) has to do that in a generic way (ie: way: it cannot know anything about any robot's specific implementation, or we could not all reuse the same JSC), hiding JSC. Hiding such details as "ticks" and "encoders" from the JSC (and other controllers in ros_control) is the task of the hardware_interface.

This piece of the ros_control stack is the interface to the hardware, and it performs a number of functions:

  1. it takes are of converting whatever units the robot hw uses into ROS standard units (REP-103)
  2. it provides a way to communicate with the hw (ie: using a serial bus, a fieldbus (ethercat, canbus, powerlink, profinet, profibus, ..), plain ethernet, TCP or UDP sockets, GPIO, direct memory registers, etc, etc)
  3. it takes care of any special initialisation routines or procedures that are needed to put the hardware in a state where it can actually be controlled
  4. it deals with error handling and recovery

And most (all?) of this is intended to abstract away implementation details about the robot for one purpose: if we hide all (most) knowledge of the actual hardware being used/addressed behind the hardware_interface, we can reuse as much of ros_control as possible, as none of the controllers (for instance) need to know anything about "encoders", "ticks" or any such things. This is the main idea behind ros_control (and in fact all of software engineering where abstraction is used to hide "implementation details" as they are called).

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders, are they ticks, ticks per meter or rad?

I hope you already know the answer to this now, but just to make it clear: they are not ticks, but the units that we've standardised on in ROS. So:

  • position: radians or metres (for revolute and prismatic joints respectively)
  • velocity: radians/sec or metres/sec (idem)
  • effort: Newtons or Newton metres (idem)

The hardware_interface will have to already have performed the conversion.

and if it was ticks, where can I provide the Radius of the wheels to the Controller?

I hope this one is already clear now as well: the controller does not do any conversion of units, so it does not need to know about ticks or wheel radii.

If you're thinking about odometry, then keep in mind that there are two levels of sensor data processing here: first from hw specific units to ROS units (reponsibility of the hardware_interface) and second from joint state to vehicle state.

In ros_control, for wheeled platforms, the latter is typically done by something like the diff_drive_controller. It is that controller that must know something about wheel radii, as it has to convert joint velocities into vehicle velocities and vice versa (ie: state and setpoints).

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders

To start (and this is slightly pedantic), but joint_state_controller (JSC) does not read from your robot's encoders. It retrieves joint state through something called a JointStateInterface and this state is comprised of position, velocity and effort.

The "only" task of the JSC is to take that state, convert it into a sensor_msgs/JointState message and publish it.

As this "controller" (and I place this in quotes as it doesn't really control anything, but that's just ros_control nomenclature) has to do that in a generic way: it cannot know anything about any robot's specific implementation, or we could not all reuse the same JSC. Hiding such details as "ticks" and "encoders" from the JSC (and other controllers in ros_control) is the task of the hardware_interface.

This piece of the ros_control stack is the interface to the hardware, and it performs a number of functions:

  1. it takes are of converting whatever units the robot hw uses into ROS standard units (REP-103)
  2. it provides a way to communicate with the hw (ie: using a serial bus, a fieldbus (ethercat, canbus, powerlink, profinet, profibus, ..), plain ethernet, TCP or UDP sockets, GPIO, direct memory registers, etc, etc)
  3. it takes care of any special initialisation routines or procedures that are needed to put the hardware in a state where it can actually be controlled
  4. it deals with error handling and recovery

And most (all?) of this is intended to abstract away implementation details about the robot for one purpose: if we hide all (most) knowledge of the actual hardware being used/addressed behind the hardware_interface, we can reuse as much of ros_control as possible, as none of the controllers (for instance) need to know anything about "encoders", "ticks" or any such things. This is the main idea behind ros_control (and in fact all of software engineering where abstraction is used to hide "implementation details" as they are called).

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders, are they ticks, ticks per meter or rad?

I hope you already know the answer to this now, but just to make it clear: they are not ticks, but the units that we've standardised on in ROS. So:

  • position: radians or metres (for revolute and prismatic joints respectively)
  • velocity: radians/sec or metres/sec (idem)
  • effort: Newtons or Newton metres (idem)

The hardware_interface will have to already have performed the conversion.conversion. And again: this is read from the hardware_interface, not encoders or the robot directly.

and if it was ticks, where can I provide the Radius of the wheels to the Controller?

I hope this one is already clear now as well: the controller does not do any conversion of units, so it does not need to know about ticks or wheel radii.

If you're thinking about odometry, then keep in mind that there are two levels of sensor data processing here: first from hw specific units to ROS units (reponsibility of the hardware_interface) and second from joint state to vehicle state.

In ros_control, for wheeled platforms, the latter is typically done by something like the diff_drive_controller. It is that controller that must know something about wheel radii, as it has to convert joint velocities into vehicle velocities and vice versa (ie: state and setpoints).

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders

To start (and this is slightly pedantic), but joint_state_controller (JSC) does not read from your robot's encoders. It retrieves joint state through something called a JointStateInterface and this state is comprised of position, velocity and effort.

The "only" task of the JSC is to take that state, convert it into a sensor_msgs/JointState message and publish it.

As this "controller" (and I place this in quotes as it doesn't really control anything, but that's just ros_control nomenclature) has to do that in a generic way: it cannot know anything about any robot's specific implementation, or we could not all reuse the same JSC. Hiding such details as "ticks" and "encoders" from the JSC (and other controllers in ros_control) is the task of the hardware_interface.

This piece of the ros_control stack is the interface to the hardware, and it performs a number of functions:

  1. it takes are of converting whatever units the robot hw uses into ROS standard units (REP-103)
  2. it provides a way to communicate with the hw (ie: using a serial bus, a fieldbus (ethercat, canbus, powerlink, profinet, profibus, ..), plain ethernet, TCP or UDP sockets, GPIO, direct memory registers, etc, etc)
  3. it takes care of any special initialisation routines or procedures that are needed to put the hardware in a state where it can actually be controlled
  4. it deals with error handling and recovery

And most (all?) of this is intended to abstract away implementation details about the robot for one purpose: if we hide all (most) knowledge of the actual hardware being used/addressed behind the hardware_interface, we can reuse as much of ros_control as possible, as none of the controllers (for instance) need to know anything about "encoders", "ticks" or any such things. This is the main idea behind ros_control (and in fact all of software engineering where abstraction is used to hide "implementation details" as they are called).

I'm really confused about what are the data joint_state_controller acquires from the Robot's Encoders, are they ticks, ticks per meter or rad?

I hope you already know the answer to this now, but just to make it clear: they are not ticks, but the units that we've standardised on in ROS. So:

  • position: radians or metres (for revolute and prismatic joints respectively)
  • velocity: radians/sec or metres/sec (idem)
  • effort: Newtons or Newton metres (idem)

The hardware_interface will have to already have performed the conversion. And again: this is read from the hardware_interface, not encoders or the robot directly.

and if it was ticks, where can I provide the Radius of the wheels to the Controller?

I hope this one is already clear now as well: the controller does not do any conversion of units, so it does not need to know about ticks or wheel radii.

If you're thinking about odometry, then keep in mind that there are (at least) two levels of sensor data processing here: first from hw specific units to ROS units (reponsibility of the hardware_interface) and second from joint state to vehicle state.

In ros_control, for wheeled platforms, the latter is typically done by something like the diff_drive_controller. It is that controller that must know something about wheel radii, as it has to convert joint velocities into vehicle velocities and vice versa (ie: state and setpoints).