srmainwaring / curio

ROS packages to control a version of Roger Chen's Sawppy Rover.
Other
57 stars 20 forks source link

Question on your Ackermann Implementation #5

Closed callen5914 closed 4 years ago

callen5914 commented 4 years ago

Greetings,

I was reviewing your implementation of the Ackermann Controller. Only because I am trying to research for my own implementation.

I did notice some of your code is commented out. Is this because you haven't succeeded yet? Or just trimming features until it makes sense to implement?

So my rover is really an ATV with an electric motor and we have a URDF file to represent this for gazebo. I am lost on the actual steps needed to implement the provided Ackermann Controller from ROS controlls.

Do I need to write a custom plugin? Do I need a custom C++ file?

I have tried to follow their steps and no matter what I do the Gazebo sim never moves or the error pops up saying it couldn't load the controller interface.

Cheers,

srmainwaring commented 4 years ago

The core functionality of the ackermann controller code is working and used in the Gazebo simulations in curio_gazebo. I adapted the code from the diff_drive_controller which supports a number of additional features I did not require for a first version. These include support for dynamic reconfiguration, parameter multipliers, and state publishing. Dynamic reconfiguration of the parameter multipliers is useful for calibrating a physical robot as it lets you tune parameters to adjust the measured velocity and turn radius to observed quantities while the robot is running.

If you are planning to just use the controller in a simulation you don't need to write a custom plugin as the package gazebo_ros_control contains a default implementation. You will need to add a <gazebo> section to your robot description to include the plugin:

<gazebo>
     <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
           <robotNamespace>/</robotNamespace>
            <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
            <legacyModeNS>false</legacyModeNS>
        </plugin>
</gazebo>

Take a look at https://github.com/srmainwaring/curio/blob/master/curio_description/urdf/curio.urdf.xacro for more details. You will also need to provide config files for the controllers and set up the Gazebo launch files to bring everything in. See https://github.com/srmainwaring/curio/blob/master/curio_gazebo/launch/curio_spawn.launch for an example.

If you are able to get the empty world simulation for curio running that will give you a base version to start from for your own robot and establish whether you have all the dependencies installed. If you have any problems with that let me know here and I'll try to help out.

For a physical rover you will need to write a C++ class implementing the RobotHW interfaces. I have not used this in curio yet because the community building Sawppy rovers seems to work mostly in Python and I was targeting that first. I do have an example for another rover if you need a starter or I can recommend the code for the Clearpath Husky robot which also uses the ros_control framework.

callen5914 commented 4 years ago

@srmainwaring,

Thanks for the extremely detailed response. It's refreshing because you are the first to be so helpful!

Our project is going to have a physical 4 wheeled ATV fully converted to electric. So we have a BLDC mounted to the steering column (the original handlebars have been removed) and a nicely sized brushless servo motor connected to the front differential (yeah, it's a front wheel drive now). This platform will eventually host IMUs, GPS, Cameras and Lasers.

Per the guidance of an actual ROS developer, we have been trying to succeed in Gazebo first. So we have a basic URDF file. It has a rectangular body and 4 cylinders to act as wheels. We have two very small links between the body and the front wheels to simulate the steering links.

Per the wiki I created a yaml file:

ackermann_steering_bot_controller:
  type: "ackermann_steering_controller/AckermannSteeringController"
  rear_wheel: "rear_wheel_joint"
  front_steer: "front_steer_joint"

  virtual_rear_wheels: ["right_rear_axle", "left_rear_axle"]
  virtual_front_wheels: ["right_front_axle", "left_front_axle"]
  virtual_front_steers: ["right_steering_joint", "left_steering_joint"]

  pose_covariance_diagonal:
    [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
  twist_covariance_diagonal:
    [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]

I read towards the bottom of that wiki page you would need the plugin and the add the lines to the urdf file.

<!-- Gazebo plugin for ROS Control -->
    <gazebo>
        <!-- <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
            <robotNamespace>/ursa_bot</robotNamespace>
            <robotSimType>ackermann_steering_bot_hw_sim/AckermannSteeringBotHwSim</robotSimType>
        </plugin> -->
        <!-- <plugin name="gazebo_ros_control" filename="libursa_bot_ctrl.so">
            <robotNamespace>/ursa_bot</robotNamespace>
            <robotSimType>ackermann_steering_bot_hw_sim/AckermannSteeringBotHwSim</robotSimType>
        </plugin> -->
        <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
            <robotNamespace>/ursa_bot</robotNamespace>
            <robotSimType>ackermann_steering_bot_hw_sim/AckermannSteeringBotHwSim</robotSimType>
        </plugin>
    </gazebo>

In there explanation, they say you need to also make a front_steer and rear_wheel link accompanied with the joints and transmissions.

<link name="front_steer">
        <visual>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
            <geometry>
                <cylinder radius="${front_wheel_diameter/2}" length="${front_wheel_width/2}"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
            <geometry>
                <cylinder radius="${front_wheel_diameter/2}" length="${front_wheel_width/2}"/>
            </geometry>
        </collision>
        <xacro:default_inertial mass="${front_wheel_mass}"/>
    </link>
    <link name="rear_wheel">
        <visual>
            <origin xyz="0.0 0.0 0.0" rpy="${degrees_90} 0.0 0.0"/>
            <geometry>
                <cylinder radius="${front_wheel_diameter/2}" length="${front_wheel_width/2}"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0.0 0.0 0.0" rpy="${degrees_90} 0.0 0.0"/>
            <geometry>
                <cylinder radius="${front_wheel_diameter/2}" length="${front_wheel_width/2}"/>
            </geometry>
        </collision>
        <xacro:default_inertial mass="${front_wheel_mass}"/>
    </link>

    <joint name="front_steer_joint" type="revolute">
        <parent link="base_link"/>
        <child link="front_steer"/>
        <axis xyz="0.0 0.0 0.1"/>
        <origin xyz="0.7 0.0 0.0" rpy="0.0 0.0 0.0"/>
        <limit lower="-0.50" upper="0.50" effort="1000" velocity="3"/>
    </joint>

    <joint name="rear_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="rear_wheel"/>

        <axis xyz="0.0 1.0 0.0"/>
        <origin xyz="-0.70 0.0 0.0" rpy="0.0 0.0 0.0"/>
        <limit effort="1000.0" velocity="3.0"/>
    </joint>

    <transmission name="front_steer_joint_trans">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="front_steer_joint">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="front_steer_joint_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>

    <transmission name="rear_wheel_joint_trans">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="rear_wheel_joint">
            <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
        </joint>
        <actuator name="rear_wheel_joint_motor">
            <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>

Now when fire that up, and switch gazebo over to wire frame view mode, I can see the two parts I added to the bot and they are moving but the actual bot parts I am expecting to see driving around my screen never move. You will also notice my URDF gazebo plugin was not made properly. I will fix that. Does anything else come to mind?

Cheers,

callen5914 commented 4 years ago

@srmainwaring,

Yes so I just tried running your curio (very cool looking btw) and I get an error on empty world launch.

[ERROR] [1584920185.457238875]: Could not load class ackermann_drive_controller/AckermannDriveController': Could not find library corresponding to plugin ackermann_drive_controller/AckermannDriveController. Make sure the plugin description XML file has the correct name of the library and that the library actually exists.

[ERROR] [1584920185.457572997]: Could not load controller 'ackermann_drive_controller' because controller type 'ackermann_drive_controller/AckermannDriveController' does not exist.

[ERROR] [1584920185.457712213]: Use 'rosservice call controller_manager/list_controller_types' to get the available types

[ERROR] [1584920186.458783, 0.000000]: Failed to load ackermann_drive_controller

Is this because I actually have to download the ros_controllers repo. I have it installed using sudo apt install.

srmainwaring commented 4 years ago

Am I right in thinking you're aiming to get the ros_controllers: ackerman_steering_controller up and running? (http://wiki.ros.org/ackermann_steering_controller?distro=melodic.) The config yaml you've provided appears to be for that controller rather than the one in this repository. They are different - my controller is for a six wheeled Curiosity style rover. The four steering joints can be controlled independently and each of the six wheel velocities are also independently controlled. That allows the rover to complete an in-place turn like a differential drive robot, something a car-style steering rover cannot do. Perhaps Ackermann is not a good name, as strictly speaking that refers to the link to tie the steering angle not the dynamics model, but the JPL guys used the terminology in their Open Source Rover documents and I've adopted it.

From what I gather the ros_controllers: ackerman_steering_controller controls just two joints: a velocity controlled rear wheel and a position controlled front wheel - both assumed to be on the vehicle's centre line (i.e. the kinematic bicycle model).

In your yaml file you have provided parameters for

virtual_rear_wheels: ["right_rear_axle", "left_rear_axle"]
...

and I'm not sure how these relate to the ackermann_steering_controller/AckermannSteeringController?

Your gazebo plugin references:

<robotSimType>ackermann_steering_bot_hw_sim/AckermannSteeringBotHwSim</robotSimType>

which I don't think will work with the gazebo_ros_control plugins. I think the plugin xml should be:

<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    <robotNamespace>/ursa_bot</robotNamespace>
    <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
    <legacyModeNS>false</legacyModeNS>
</plugin>

If you can provide the full urdf model for the robot I could take a look at it. What I think you're after is to use the controller to drive the rear axle (no-diff), and a front steering joint from the steering column which is then connected to the wheels by linkages (that is if you want to model the full steering train). That's a bit more involved to model in Gazebo, and is a little like the rocker-bogie differential which I've modelled in the curio rover. You may not be able to model it directly in urdf if the kinematics have a closed chain, but Gazebo's SDF can describe this type of arrangement. If you are going down this route then you'll also need to use the libgazebo_ros_joint_state_publisher plugin for all the non-actuated joints and may need to spend some time tuning the physics engine as I found that the simulation can be quite sensitive to the physics constraints imposed on the joints and the type of solver used.

Just seen your second post: that looks like Gazebo is not finding the ackermann_drive_controller package? Did 'catkin build' followed by source devel/setup.bash all work ok?

callen5914 commented 4 years ago

@srmainwaring,

If you can provide the full urdf model for the robot I could take a look at it.

In an effort to keep the thread shorter I have created a gist for you to take a look. For now my urdf is there along with my launch file. I am happy to add whichever other documents you would like to see.

They are different - my controller is for a six wheeled Curiosity style rover.

Your rover wouldn't quite launch for me either but now that I know about your project I am super interested in trying to build one myself. I host large STEM camps every summer and I think the kids would love this!

srmainwaring commented 4 years ago

Great, I'll take a look.

Full credit for the rover design goes to Roger Chen:

If you do build one and use it for teaching I think he'd be very happy to hear about it.

If you are having trouble getting my ROS code to run and want to follow up I'd be happy to help out with that too. Create an new issue with the details and I'll work through it.

srmainwaring commented 4 years ago

Edit: I've re-written my earlier comment after stepping through steer_bot_hardware_gazebo and resolving the origin of segmentation faults.

  1. I've provided a simple example simulation here: https://github.com/srmainwaring/steer_bot.

  2. Using a patched version of the steer_drive_ros stack for ROS melodic that is awaiting PR approval (https://github.com/tsedl/steer_drive_ros.git), you can modify the test example in steer_drive_controller/test/common/launch/view_steerbot.launch to use steer_bot_hardware_gazebo and get the model running correctly in Gazebo and rviz. This will give you what you need for your robot.

  3. I'll add the steer_drive example to my simple example above, as it requires changes to the URDF, launch files, and controller configuration. Unfortunately the steer_bot_hardware_gazebo segmentation faults with no warnings when the controller parameters are not set up correctly, which lead me to initially believe it was broken. Some additional checks in the code would help.

srmainwaring commented 4 years ago

The example is now completed and working with the steer_drive_ros stack. You can change the dimensions for your ursa_bot or use it as a guide. I'm going to close this issue now and if you've any problems with the demo open a new issue on https://github.com/srmainwaring/steer_bot.