neo_linear_axis

Linear axis is an add-on component for the Neobotix mobile platforms. This documentation gives you a brief overview of the linear axis ROS package.

neo_linear_axis package contains the hardware component for the linear axis and as well as contains the necessary MoveIt support. In the ros2_control framework, hardware component is one of the modules in the frameworks architecture, which is responsible for establishing communication between the physical hardware. These components are created as a plugin, making them modular and independent of other components in the system, thus allowing the linear axis to be easily integrated with any robot arm that has ROS 2 support. Further, ros2_control environment supports different controllers that is capable of sending position, velocity and torque commands to the hardware. Since MoveIt requires JointTrajectoryController, the same controller has been configured for the linear axis. Additional to the JointTrajectoryController, JointStateBroadcasters are required for publishing the necessary joint_states.

Note

Position and velocity states can be read and written for this particular linear axis setup.

More about hardware components can be found here.

Teachnical drawing

../_images/linear_axis_measurement.png

Sensors

The linear axis consists of two limit switches placed at the lower and the upper end of the linear axis.

For MPO 700, the position of the lower limit switch and the upper limit switch can be seen in the image attached above.

Sensor elements are also configured has hardware components. gpio tag has been utilized for defining the limit switches in the URDF. More information regarding hardware_interface types can be found here.

Configuring the Package

By default the URDF of the Neobotix robot contains the necessary links, joints and the URI to the meshes of the the axis. Further, the ROS 2 hardware interface along with the JointTrajectoryController is configured from the URDF.

The URDF of the robot can be found under your_robot/robot_model/mpo_700/mpo_700.urdf.

The config file for the joint trajectory controllers can be found under your_robot/configs/controller/controller.yaml. The controller is named as linear_axis_controller, which is inturn set to the type joint_trajectory_controller/JointTrajectoryController.

Please look into ros2_control website for the details about the controller parameters

Note

It’s advised not to add and tune any of the parameters that is not the delivered configuration. Please consult with us, if you have any special questions with related to the configuration.

There are also pre-defined and custom parameters for the hardware components, which can be tuned from the URDF depending upon the application. The list of parameters are as follows:

pre-defined parameters

The max velocity, upper and the lower limit of the linear axis is represented under the linear_axis_slide_joint:

<limit lower="0.0" upper="0.68" effort="0.0" velocity="0.15"/>

Attention

Please note that, the lower limit should always point to the position where slide meets the lowest limit switch and the upper limit should point to the position where slide meets the upper limit switch.

Note

A safety mechanism is in place, that does not allow the slide to move beyond the position of the limit switches.

Custom parameters

Field Description Default Value
can_iface Can interface to which the motor is connected can0
timeout Motor time out 0.2
control_rate Motor cycle rate for reading data 100.0
initial_pose Initial pose represents the start pose, which the linear axis move to after homing 0.1

Launching

Neobotix platforms with Linear axis by default would have been already configured with steps defined above. The controller manager package enables the necessary hardware interface as well as the JointStateBroadcaster and the JointTrajectoryController. All the necessary steps are included in the bringup launch. More information about the bringup can be found at Starting with ROS on the Robot.

Once the robot bringup has started. The linear axis will perform the homing manuver after which it moves to the pre-defined initial pose. The initial_pose can be configured from the URDF.

Attention

The JointTrajectoryController is initialized, configured and set to inactive state on bringup. JTC does not have to be active while the linear axis is homing. Keeping it active would cause the axis to go the 0.0m position after reaching the pre-configured initial pose. In contrary JTC will hold the position, when it is activated, once the complete homing process is finished.

In order to activate the controller

ros2 control set_controller_state linear_axis_controller active

More about ROS 2 CLI Framework.

Once the linear_axis_controller is activated, you will be able to send the necessary trajectory either through rqt_joint_trajectory_controller or through MoveIt, which will be discussed later.

Note

rqt_joint_trajectory_controller is utilized only for quick prototyping. It is strongly recommended either to use the ros2 action interface for sending the goals to axis or using the MoveIt to plan and send trajectories to the linear_axis_controller.

Start the rqt_joint_trajectory_controller using the following command

ros2 run rqt_joint_trajectory_controller rqt_joint_trajectory_controller

Select the controller manager and the controller. Then specify the goal position for your linear axis.

Attention

While sending goals using the rqt_joint_trajectory_controller at a speed scaling of 50 %, the axis is expected to oscillate while reaching the goal location. We observed that, the oscillation reduces by adjusting the goal tolerances. However no oscillations were inferred with the pre-configured parameters while the speed scaling was set to 100% nor neither while using MoveIt.

The joint state about the linear axis can be read in the joint_states topic. The joint state message contains the position and velocity of the linear axis. If you also want to read the state of the limit switches, you can read the state from the dynamic_joint_states topic. Note dynamic_joint_states also contains the position and the velocity of the linear axis. First index is the limit switch mounted to the top part of the linear axis and the second index is the limit switch mounted to the bottom part of the linear axis.

Once the JointTrajectoryController has been activated, the linear axis can be controlled using the MoveIt. Please refer to the MoveIt documentation for more information about the MoveIt.

The MoveIt package can be launched using the following command

ros2 launch neo_linear_axis move_group.launch.py

Note

The MoveIt launch file is configured to load the necessary MoveIt Controllers. Please do not change the configuration of the launch file.

Once the MoveIt is launched, it is also required to start the RViz for MoveIt. The RViz can be started using the following command

ros2 launch neo_linear_axis moveit_rviz.launch.py

By default, we have configure the linear axis group with 2 pre-poses. The first pre-pose, top would take the robot all the way to the top, i.e. to the upper limit switch. The second pre-pose, down would take the robot 0.1 m above the lower limit switch.

Note

In order to achieve the full speed using MoveIt, please set the speed scaling to 100% in the MoveIt GUI.

Known issues

JTC keeps sending the last velocity command, even after cancelling the goal in MoveIt. This is an issue originated in the ROS 2 control. More about it can be read from here: https://github.com/ros-controls/ros2_controllers/issues/683 Therefore, the temporary workaround for this was to compare the velocity commands and stop the motion.

Attention

The workaround solution might stop the axis briefly, while executing the MoveIt / JTC goal. This issue will be fixed in the next versions of the ROS 2 control.

Note

Neobotix will remove the workaround solution once the issue is fixed in the ROS 2 control.

The permanent fix can be found here: https://github.com/ros-controls/ros2_controllers/pull/801