Change actuators to D.C. motors.
authorWalter Fetter Lages <w.fetter@ieee.org>
Sun, 18 Nov 2018 06:58:20 +0000 (04:58 -0200)
committerWalter Fetter Lages <w.fetter@ieee.org>
Sun, 18 Nov 2018 06:58:20 +0000 (04:58 -0200)
tatuira_bringup/CMakeLists.txt
tatuira_bringup/config/bypass.yaml
tatuira_bringup/config/pid.yaml
tatuira_bringup/package.xml
tatuira_description/xacro/back.urdf.xacro
tatuira_description/xacro/link_joint.urdf.xacro
tatuira_description/xacro/main.urdf.xacro

index ae15541..118934a 100644 (file)
@@ -8,7 +8,7 @@ project(tatuira_bringup)
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 ## is used, also find other catkin packages
 find_package(catkin REQUIRED COMPONENTS
-  effort_controllers
+  voltage_controllers
   joint_state_controller
 #  linearizing_controllers
 #  linearizing_controllers_msgs
index cc6b5ee..3091f14 100644 (file)
@@ -1,11 +1,22 @@
 right_wheel_controller:
-        type: effort_controllers/JointEffortController
+        type: voltage_controllers/JointVoltageController
         joint: right_rim_joint
 
 left_wheel_controller:
-        type: effort_controllers/JointEffortController
+        type: voltage_controllers/JointVoltageController
         joint: left_rim_joint
 
 joint_states_publisher:
         type: joint_state_controller/JointStateController
         publish_rate: 100
+
+gazebo_ros_electrical:
+        dcmotor:
+                right_rim_joint:
+                        Ra: 0.3434
+                        La: 3.16
+                        Kt: 0.0899
+                left_rim_joint:
+                        Ra: 0.3434
+                        La: 3.16
+                        Kt: 0.0899
index 8494efa..ceb1bad 100644 (file)
@@ -1,13 +1,24 @@
 right_wheel_controller:
-        type: effort_controllers/JointVelocityController
+        type: voltage_controllers/JointVelocityController
         joint: right_rim_joint
         pid: {p: 0, i: 0, d: 0}   
 
 left_wheel_controller:
-        type: effort_controllers/JointVelocityController
+        type: voltage_controllers/JointVelocityController
         joint: left_rim_joint
         pid: {p: 0, i: 0, d: 0}
 
 joint_states_publisher:
         type: joint_state_controller/JointStateController
         publish_rate: 100
+
+gazebo_ros_electrical:
+        dcmotor:
+                right_rim_joint:
+                        Ra: 0.3434
+                        La: 3.16
+                        Kt: 0.0899
+                left_rim_joint:
+                        Ra: 0.3434
+                        La: 3.16
+                        Kt: 0.0899
index ccb4945..cfd1ae2 100644 (file)
   <!-- Use test_depend for packages you need only for testing: -->
   <!--   <test_depend>gtest</test_depend> -->
   <buildtool_depend>catkin</buildtool_depend>
-  <build_depend>effort_controllers</build_depend>
+  <build_depend>voltage_controllers</build_depend>
   <build_depend>joint_state_controller</build_depend>
   <!--
   <build_depend>linearizing_controllers</build_depend>
   <build_depend>linearizing_controllers_msgs</build_depend>
   <build_depend>nonsmooth_backstep_controller</build_depend>
   -->
-  <run_depend>effort_controllers</run_depend>
+  <run_depend>voltage_controllers</run_depend>
   <run_depend>joint_state_controller</run_depend>
   <!--
   <run_depend>linearizing_controllers</run_depend>
index 0976ed7..ba1a181 100644 (file)
                <transmission name="${name}_transmission">
                        <type>transmission_interface/SimpleTransmission"</type>
                        <joint name="${name}_rim_joint">
-                               <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+                               <hardwareInterface>electrical_interface/VoltageJointInterface</hardwareInterface>
                        </joint>
                        <actuator name="${name}_motor">
                                <mechanicalReduction>1</mechanicalReduction>
index 0f01741..5d3000f 100644 (file)
@@ -46,6 +46,7 @@
                        <child link="${name}_link"/>
                        <axis xyz="${axis}"/>
                        <origin xyz="${xyz}" rpy="${rpy}" />
+                       <limit effort="3.2" velocity="387.46" />
                </joint>
                
                <gazebo reference="${name}_link">
index 1933c09..a703853 100644 (file)
@@ -73,6 +73,7 @@
        <gazebo>
                <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
                        <!--<robotNamespace>/tatuira</robotNamespace>-->
+                       <robotSimType>gazebo_ros_electrical/DCmotorRobotHWSim</robotSimType>
                        <controlPeriod>0.001</controlPeriod>
                </plugin>
        </gazebo>