0
$\begingroup$

I'm wondering if someone has some ideas about how to make a prismatic axis work with ros2 controllers.

I am using a UR10e which is mountd on an igus drylin ZLW 7th Axis controlled by Dryve D1. I have an API for it to communicate with the Axis to initialize, run and control it. It has an encoder so after homing I can extrapolate the exact position, velocity and other info.

I send the move command using the function xAxis.profilePositionAbs_Async(pos, setvel, acc, dec);

I have written a hardware interface with the following functions:

std::vector<hardware_interface::StateInterface>
RRBotSystemPositionOnlyHardware::export_state_interfaces()
{
  std::vector<hardware_interface::StateInterface> state_interfaces;

    state_interfaces.emplace_back(hardware_interface::StateInterface(
    axisName, hardware_interface::HW_IF_POSITION, &pos));


  return state_interfaces;
}

std::vector<hardware_interface::CommandInterface>
RRBotSystemPositionOnlyHardware::export_command_interfaces()
{
  std::vector<hardware_interface::CommandInterface> command_interfaces;
    command_interfaces.emplace_back(hardware_interface::CommandInterface(
    axisName, hardware_interface::HW_IF_POSITION, &pos));

  return command_interfaces;
}

hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_deactivate(
  const rclcpp_lifecycle::State & /*previous_state*/)
{
    xAxis.waitForReady();
    xAxis.setShutdown();

    // Gracefully close everything down
    
    close(xAxis.sock);
  return hardware_interface::CallbackReturn::SUCCESS;
}

hardware_interface::return_type RRBotSystemPositionOnlyHardware::read(
  const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{

  pos=xAxis.getCurrentPosInMM()/1000;
  std::cout << "position in meters" << pos << std::endl;

  return hardware_interface::return_type::OK;
}

hardware_interface::return_type RRBotSystemPositionOnlyHardware::write(
  const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{

  xAxis.profilePositionAbs_Async(pos*1000, setvel, acc, dec);

  return hardware_interface::return_type::OK;
}

Now the problem is, as the profilePositionAbs_Async function is within the write function it gets called every loop, meaning the movement gets rerun continuously leading to a continuous accel- and deceleration.

Also I seem to get issues due to the position parameter being used in both the state and command interface.

So i was wondering, what is the best way to incorporate such an axis in a joint trajectory controller and handle the state/command interference

EDIT: in order to elaborate on @ChristophFroehlich's reply i have added the description of the possible functions to interact with the driver:

        void profilePositionAbs(float position, float velo, float accel, float decel=0); // Function "Profile Position Mode"; Move to an absolute position with given velocity, acceleration and deceleration
        void profilePositionRel(float position, float velo, float accel, float decel=0); // Function "Profile Position Mode"; Move to an relative position with given velocity, acceleration and deceleration
        void profileVelocity(float velo, float accel, float decel=0); // Function "Profile Position Mode"; Move with a set target velocity, acceleration and deceleration; Movement starts directly when the target velocity is not 0```
$\endgroup$
2
  • $\begingroup$ Hi! The problem is then, that your API only supports a position interface with max. velocity, acceleration+deceleration and is designed to send only one point? So the API or the drive does the trajectory generation itself to reach the target? $\endgroup$ Commented Dec 15, 2023 at 9:52
  • $\begingroup$ hey @ChristophFroehlich thanks for your reply! that is one way to interact with the drive. you can also move it using void profileVelocity(float velo, float accel, float decel=0);. i have uploaded the possible ways to the end of the question. does that help? is it possible to control trajectory by sending out velocity commands (without position)? $\endgroup$
    – Adam
    Commented Dec 16, 2023 at 14:18

2 Answers 2

0
$\begingroup$

Without knowing details of the underlying implementation of your drive, I can only guess:

  • If the drive takes new position commands without stopping the old target, you can use position command and regularily send a new setpoint, sampled by JTC. Then the drive might have safe software-end stops implemented etc.
  • use the velocity interface of your drive, and use the joint_trajectory_controller with position control and velocity command interface. Unclear if end-stops work then?

If you use the latter one: (More information in the docs)

command_interfaces:
  - velocity

state_interfaces:
  - position
  - velocity

In the write method of the hardware component, you send the velocity to the hardware coming from the command interfaces. In the read method you get the data from your encoders, calculate the velocity from the signal, and update the state interfaces.

$\endgroup$
2
  • $\begingroup$ thanks for your solution! i will try the velocity command out on monday! the implementation i have right now is like your first proposal, however when i send a new position command it decelerates and accelerates again which is the choppy behavior i i have observed. the endstops still work as they are handled by the driver control itself and raise a flag when reached. $\endgroup$
    – Adam
    Commented Dec 16, 2023 at 21:28
  • $\begingroup$ thank you very much christoph! using a velocity interface solved my problem $\endgroup$
    – Adam
    Commented Dec 18, 2023 at 13:03
0
$\begingroup$

You do not appear to be using hardware_interface correctly. I'm going to assume the context is position control, meaning the upper layers of ros_control send position commands to this API.

The StateInterface should report the actual current position value, which you are expected to read from the hardware using the manufacturer's library. Note: this is NOT the last-received target position.

The CommandInterface is used to send a target position. The target position may be sent periodically, so if you have a smart downstream controller and it's already busy executing a command, your hardware_interface code should NOT pass a redundant command downstream.

Now after explaining all that, you shouldn't be using a position interface! It's likely much cleaner to implement a velocity interface both upward and downward.

$\endgroup$
1
  • $\begingroup$ well with position control i dont seem to be having problems since it just gives a goal and executes it. the state interface is also reading the current position from the driver encoder, im not sure why you assumed something else. and the command interface is sending a target position, just with the position control it is held by the same variable for some reason? i also did not want to implement a blocking position control because that would have stopped me from using waypoints properly. I will try out velocty control on monday, i would greatly appreciate a field example. $\endgroup$
    – Adam
    Commented Dec 16, 2023 at 21:31

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.