Skip to content

Commit

Permalink
Merge pull request #11 from Halodi/feature/LeftWheelIMU
Browse files Browse the repository at this point in the history
Feature/left wheel imu
  • Loading branch information
jespersmith authored Apr 28, 2021
2 parents b0eb024 + 6da4851 commit a656e18
Show file tree
Hide file tree
Showing 7 changed files with 200 additions and 35 deletions.
33 changes: 28 additions & 5 deletions eve_r3_description/sdf/eve_r3.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,14 @@
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
<stddev>0.0022</stddev>
<bias_mean>0.0035</bias_mean>
<bias_stddev>0.001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<stddev>0.031</stddev>
<bias_mean>0.006</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
Expand Down Expand Up @@ -303,6 +303,29 @@
</geometry>

</visual>
<velocity_decay/>
<sensor name="imu_left" type="imu">
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0022</stddev>
<bias_mean>0.0174533</bias_mean>
<bias_stddev>0.0001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.031</stddev>
<bias_mean>0.012</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">0.23412 0.1925 0.013 0 -0 0</pose>
</sensor>
<gravity>1</gravity>
<velocity_decay/>
</link>
Expand Down
33 changes: 28 additions & 5 deletions eve_r3_description/sdf/eve_r3_robotiq_2f_85.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,14 @@
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
<stddev>0.0022</stddev>
<bias_mean>0.0035</bias_mean>
<bias_stddev>0.001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<stddev>0.031</stddev>
<bias_mean>0.006</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
Expand Down Expand Up @@ -303,6 +303,29 @@
</geometry>

</visual>
<velocity_decay/>
<sensor name="imu_left" type="imu">
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0022</stddev>
<bias_mean>0.0174533</bias_mean>
<bias_stddev>0.0001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.031</stddev>
<bias_mean>0.012</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">0.23412 0.1925 0.013 0 -0 0</pose>
</sensor>
<gravity>1</gravity>
<velocity_decay/>
</link>
Expand Down
33 changes: 28 additions & 5 deletions eve_r3_description/sdf/eve_r3_robotiq_hand-e.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,14 @@
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
<stddev>0.0022</stddev>
<bias_mean>0.0035</bias_mean>
<bias_stddev>0.001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<stddev>0.031</stddev>
<bias_mean>0.006</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
Expand Down Expand Up @@ -303,6 +303,29 @@
</geometry>

</visual>
<velocity_decay/>
<sensor name="imu_left" type="imu">
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0022</stddev>
<bias_mean>0.0174533</bias_mean>
<bias_stddev>0.0001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.031</stddev>
<bias_mean>0.012</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">0.23412 0.1925 0.013 0 -0 0</pose>
</sensor>
<gravity>1</gravity>
<velocity_decay/>
</link>
Expand Down
34 changes: 29 additions & 5 deletions eve_r3_description/urdf.in/eve_r3_leg.in.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -200,21 +200,45 @@
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
<stddev>0.0022</stddev>
<bias_mean>0.0035</bias_mean>
<bias_stddev>0.001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<stddev>0.031</stddev>
<bias_mean>0.006</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">-0.057 0.0 0.39790 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<sensor name="imu_left" type="imu">
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0022</stddev>
<bias_mean>0.0174533</bias_mean>
<bias_stddev>0.0001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.031</stddev>
<bias_mean>0.012</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">0.23412 0.1925 0.013 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
Expand Down
34 changes: 29 additions & 5 deletions eve_r3_description/urdf/eve_r3.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -217,21 +217,45 @@ limitations under the License.
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
<stddev>0.0022</stddev>
<bias_mean>0.0035</bias_mean>
<bias_stddev>0.001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<stddev>0.031</stddev>
<bias_mean>0.006</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">-0.057 0.0 0.39790 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<sensor name="imu_left" type="imu">
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0022</stddev>
<bias_mean>0.0174533</bias_mean>
<bias_stddev>0.0001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.031</stddev>
<bias_mean>0.012</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">0.23412 0.1925 0.013 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
Expand Down
34 changes: 29 additions & 5 deletions eve_r3_description/urdf/eve_r3_robotiq_2f_85.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -217,21 +217,45 @@ limitations under the License.
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
<stddev>0.0022</stddev>
<bias_mean>0.0035</bias_mean>
<bias_stddev>0.001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<stddev>0.031</stddev>
<bias_mean>0.006</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">-0.057 0.0 0.39790 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<sensor name="imu_left" type="imu">
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0022</stddev>
<bias_mean>0.0174533</bias_mean>
<bias_stddev>0.0001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.031</stddev>
<bias_mean>0.012</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">0.23412 0.1925 0.013 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
Expand Down
34 changes: 29 additions & 5 deletions eve_r3_description/urdf/eve_r3_robotiq_hand-e.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -217,21 +217,45 @@ limitations under the License.
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
<stddev>0.0022</stddev>
<bias_mean>0.0035</bias_mean>
<bias_stddev>0.001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<stddev>0.031</stddev>
<bias_mean>0.006</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">-0.057 0.0 0.39790 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<sensor name="imu_left" type="imu">
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0</mean>
<stddev>0.0022</stddev>
<bias_mean>0.0174533</bias_mean>
<bias_stddev>0.0001</bias_stddev>
</rate>
<accel>
<mean>0</mean>
<stddev>0.031</stddev>
<bias_mean>0.012</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose frame="">0.23412 0.1925 0.013 0 0.0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
Expand Down

0 comments on commit a656e18

Please sign in to comment.