Skip to content

Commit

Permalink
New features for Absolem robot. (#551)
Browse files Browse the repository at this point in the history
* Absolem: Add relative positional control.

* Absolem: Added a reference to the issue blocking implementation of the differential.

* Absolem: Read flipper velocity and effort limits from the joint limits, too.

* Absolem: Preparations for setting max torque in flippers.

* Absolem: Simplify interaction with ECM using the new APIs.

* Absolem: Added TODO referencing a PR in ign-gazebo that would allow deleting the ECM shim from this package.

* Simplify the code with gazebosim/gz-sim#629 .
  • Loading branch information
peci1 authored Apr 8, 2021
1 parent 4b163b0 commit 0838122
Show file tree
Hide file tree
Showing 5 changed files with 200 additions and 130 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,20 @@
args="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos" to="flippers_cmd_pos/front_left"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_front_left_flipper_pos_rel"
args="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/front_left"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_front_left_flipper_torque"
args="/model/$(arg name)/joint/front_left_flipper_j/cmd_max_torque@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_left_flipper_j/cmd_max_torque" to="flippers_cmd_max_torque/front_left"/>
</node>

<node
pkg="ros_ign_bridge"
Expand All @@ -86,6 +100,20 @@
args="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos" to="flippers_cmd_pos/front_right"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_front_right_flipper_pos_rel"
args="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/front_right"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_front_right_flipper_torque"
args="/model/$(arg name)/joint/front_right_flipper_j/cmd_max_torque@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_right_flipper_j/cmd_max_torque" to="flippers_cmd_max_torque/front_right"/>
</node>

<node
pkg="ros_ign_bridge"
Expand All @@ -101,6 +129,20 @@
args="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos" to="flippers_cmd_pos/rear_left"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_rear_left_flipper_pos_rel"
args="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/rear_left"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_rear_left_flipper_torque"
args="/model/$(arg name)/joint/rear_left_flipper_j/cmd_max_torque@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_left_flipper_j/cmd_max_torque" to="flippers_cmd_max_torque/rear_left"/>
</node>

<node
pkg="ros_ign_bridge"
Expand All @@ -115,7 +157,22 @@
name="ros_ign_bridge_rear_right_flipper_pos"
args="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos" to="flippers_cmd_pos/rear_right"/>
</node>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_rear_right_flipper_pos_rel"
args="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/rear_right"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_rear_right_flipper_torque"
args="/model/$(arg name)/joint/rear_right_flipper_j/cmd_max_torque@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_right_flipper_j/cmd_max_torque" to="flippers_cmd_max_torque/rear_right"/>
</node>

<!-- Laser rotation control -->

<node
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@ This configuration is based BlueBotics Absolem tracked robot. The robot is equip
## Usage Instructions
The robot motion is controlled via standard `cmd_vel` commands.

Flippers can be velocity-controlled by publishing to topics `flippers_cmd_vel/front_left` (`front_right`, `rear_left`, `rear_right`) (`std_msgs/Float64`) for velocity control or topics `flippers_cmd_pos/front_left`, etc. for position control. Maximum angular velocity of the flippers is `pi/4 rad/s`. The effort limits in the model were set so that the robot can support itself with the flippers, but cannot use them to lift itself on all four flippers. This is how the real flippers work. The current position of the flippers is published to `joint_states` as `front_left_flipper_j` etc. The flippers can continuously rotate.
Flippers can be controlled by publishing to topics `flippers_cmd_vel/front_left` (`front_right`, `rear_left`, `rear_right`) (`std_msgs/Float64`) for velocity control or topics `flippers_cmd_pos/front_left`, etc. for position control. Relative positional control is available on `flippers_cmd_pos_rel/front_left` etc. Maximum angular velocity of the flippers is `pi/4 rad/s`. The effort limits in the model were set so that the robot can support itself with the flippers, but cannot use them to lift itself on all four flippers. This is how the real flippers work. The current position of the flippers is published to `joint_states` as `front_left_flipper_j` etc. The flippers can continuously rotate.

The laser rotation is velocity-controlled by publishing to topic `scanning_speed_cmd` (`std_msgs/Float64`). The laser has hard stops at `+-2.36 rad` and maximum rotation velocity is `1.2 rad/s`. The laser has an automatic controller that reverses the rotation direction at a given angle (currently ca. `1.6 rad`). The current position of the laser is published to `joint_states` as `laser_j`. The default (zero) position of the laser is such that the scanning plane is levelled with ground.
The laser rotation is velocity-controlled by publishing to topic `lidar_gimbal/roll_rate_cmd_double` (`std_msgs/Float64`). The laser has hard stops at `+-2.36 rad` and maximum rotation velocity is `1.2 rad/s`. The laser has an automatic controller that reverses the rotation direction at a given angle (currently ca. `1.6 rad`). The current position of the laser is published to `joint_states` as `laser_j`. The default (zero) position of the laser is such that the scanning plane is levelled with ground.

The robot is equipped with two more passive joints which connect the tracks to `base_link`. They are called `left_track_j` and `right_track_j`. These joints are connected via a differential with lockable brake. The differential makes sure that `angle(left_track_j) == -angle(right_track_j)` at all times. This model configuration has the differential brake applied in zero position, which means the tracks cannot move relative to the robot body.

Expand Down Expand Up @@ -42,7 +42,7 @@ The following specific sensors are declared payloads of this vehicle:
### Control
This robot is controlled by the DiffDrive plugin. It accepts twist inputs which drives the vehicle along the x-direction and around the z-axis. We add additional 8 pseudo-wheels where the robot's tracks are to better approximate a track vehicle (flippers are subdivided to 5 pseudo-wheels). Currently, we are not aware of a track-vehicle plugin for ignition-gazebo. A TrackedVehicle plugin does exist in gazebo8+, but it is not straightforward to port to ignition-gazebo. We hope to work with other SubT teams and possibly experts among the ignition-gazebo developers to address this in the future.

Flippers provide a velocity control interface, but a positional controller and a higher-level control policy are strongly suggested.
Flippers provide interfaces for velocity control and absolute and relative positional control. The positional controllers move flippers to the given position using the maximum speed of the flippers.

### Motion characteristics

Expand Down
Loading

0 comments on commit 0838122

Please sign in to comment.