forked from gazebosim/gz-sim
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Adds velocity control to JointPositionController. (gazebosim#1003)
There are times when we don't nessecarily want to tune a PID for each joint. Often we may assume that the physical robot already has a well tuned controller. This was true in the case of the mbari LRAUV. Hence, there should be a way to set position without the use of a PID controller. This commit adds a `use_velocity_commands` option which when set to true bypasses the force based PID giving a very predictable position. The `use_velocity_command` mode has a `cmd_max` which in turn can be used to set a maximum velocity which the joint can move at. Signed-off-by: Arjo Chakravarty <[email protected]> Co-authored-by: Louise Poubel <[email protected]> Signed-off-by: William Lew <[email protected]>
- Loading branch information
1 parent
ee2fd98
commit b8e0e41
Showing
4 changed files
with
305 additions
and
2 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,159 @@ | ||
<?xml version="1.0" ?> | ||
<sdf version="1.6"> | ||
<world name="default"> | ||
<plugin | ||
filename="ignition-gazebo-physics-system" | ||
name="ignition::gazebo::systems::Physics"> | ||
</plugin> | ||
<plugin | ||
filename="ignition-gazebo-scene-broadcaster-system" | ||
name="ignition::gazebo::systems::SceneBroadcaster"> | ||
</plugin> | ||
|
||
<gui fullscreen="0"> | ||
|
||
<!-- 3D scene --> | ||
<plugin filename="GzScene3D" name="3D View"> | ||
<ignition-gui> | ||
<title>3D View</title> | ||
<property type="bool" key="showTitleBar">false</property> | ||
<property type="bool" key="resizable">false</property> | ||
<property type="double" key="z">0</property> | ||
<anchor line="right" target="window" target_line="right"/> | ||
<anchor line="left" target="window" target_line="left"/> | ||
<anchor line="top" target="window" target_line="top"/> | ||
<anchor line="bottom" target="window" target_line="bottom"/> | ||
</ignition-gui> | ||
|
||
<engine>ogre</engine> | ||
<scene>scene</scene> | ||
<ambient_light>0.4 0.4 0.4</ambient_light> | ||
<background_color>0.8 0.8 0.8</background_color> | ||
<camera_pose>-1 0 1 0 0.5 0</camera_pose> | ||
</plugin> | ||
|
||
<!-- World control --> | ||
<plugin filename="WorldControl" name="World control"> | ||
<ignition-gui> | ||
<title>World control</title> | ||
<property type="bool" key="showTitleBar">false</property> | ||
<property type="bool" key="resizable">false</property> | ||
<property type="double" key="height">72</property> | ||
<property type="double" key="width">121</property> | ||
<property type="double" key="z">1</property> | ||
<anchor line="left" target="window" target_line="left"/> | ||
<anchor line="bottom" target="window" target_line="bottom"/> | ||
</ignition-gui> | ||
|
||
<play_pause>true</play_pause> | ||
<step>true</step> | ||
<start_paused>true</start_paused> | ||
|
||
</plugin> | ||
</gui> | ||
<model name="ground_plane"> | ||
<static>true</static> | ||
<link name="link"> | ||
<collision name="collision"> | ||
<geometry> | ||
<plane> | ||
<normal>0 0 1</normal> | ||
<size>100 100</size> | ||
</plane> | ||
</geometry> | ||
</collision> | ||
<visual name="visual"> | ||
<geometry> | ||
<plane> | ||
<normal>0 0 1</normal> | ||
<size>100 100</size> | ||
</plane> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
</link> | ||
</model> | ||
<model name="joint_position_controller_test"> | ||
<pose>0 0 0.005 0 0 0</pose> | ||
<link name="base_link"> | ||
<pose>0.0 0.0 0.0 0 0 0</pose> | ||
<inertial> | ||
<inertia> | ||
<ixx>2.501</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>2.501</iyy> | ||
<iyz>0</iyz> | ||
<izz>5</izz> | ||
</inertia> | ||
<mass>120.0</mass> | ||
</inertial> | ||
<visual name="base_visual"> | ||
<pose>0.0 0.0 0.0 0 0 0</pose> | ||
<geometry> | ||
<box> | ||
<size>0.5 0.5 0.01</size> | ||
</box> | ||
</geometry> | ||
</visual> | ||
<collision name="base_collision"> | ||
<pose>0.0 0.0 0.0 0 0 0</pose> | ||
<geometry> | ||
<box> | ||
<size>0.5 0.5 0.01</size> | ||
</box> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<link name="rotor"> | ||
<pose>0.0 0.0 1.0 0.0 0 0</pose> | ||
<inertial> | ||
<pose>0.0 0.0 0.0 0 0 0</pose> | ||
<inertia> | ||
<ixx>0.032</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>0.032</iyy> | ||
<iyz>0</iyz> | ||
<izz>0.00012</izz> | ||
</inertia> | ||
<mass>0.6</mass> | ||
</inertial> | ||
<visual name="visual"> | ||
<geometry> | ||
<box> | ||
<size>0.25 0.25 0.05</size> | ||
</box> | ||
</geometry> | ||
</visual> | ||
<collision name="collision"> | ||
<geometry> | ||
<box> | ||
<size>0.25 0.25 0.05</size> | ||
</box> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<joint name="j1" type="revolute"> | ||
<pose>0 0 -0.5 0 0 0</pose> | ||
<parent>base_link</parent> | ||
<child>rotor</child> | ||
<axis> | ||
<xyz>0 0 1</xyz> | ||
</axis> | ||
</joint> | ||
<plugin | ||
filename="ignition-gazebo-joint-position-controller-system" | ||
name="ignition::gazebo::systems::JointPositionController"> | ||
<joint_name>j1</joint_name> | ||
<use_velocity_commands>true</use_velocity_commands> | ||
<cmd_max>1000</cmd_max> | ||
</plugin> | ||
</model> | ||
</world> | ||
</sdf> |