Skip to content

Commit

Permalink
fixed utc time issue, now using system time + tuned ekf
Browse files Browse the repository at this point in the history
  • Loading branch information
bjajoh committed Dec 9, 2020
1 parent 7dfc079 commit af0fc40
Show file tree
Hide file tree
Showing 17 changed files with 493 additions and 69 deletions.
8 changes: 5 additions & 3 deletions common/launch/raw_data.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
<launch>
<!-- <include file="$(find mpu9250-driver)/launch/mpu9250.launch"/> -->
<include file="$(find common)/launch/tf.launch"/>
<include file="$(find mpu9250-driver)/launch/mpu9250.launch"/>
<include file="$(find ublox_gps)/launch/ublox_zed-f9p.launch"/>
</launch>
<include file="$(find common)/launch/rtk.launch"/>
<include file="$(find sbg_driver)/launch/examples/sbg_ellipseN.launch"/>
<node pkg="odrive_ros" type="odrive_basic_node.py" name="odrive_ros" output="screen"> </node>
</launch>
2 changes: 1 addition & 1 deletion common/launch/rtk.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<include file="$(find common)/launch/tf.launch"/>
<!-- <include file="$(find common)/launch/tf.launch"/> -->
<include file="$(find ublox_gps)/launch/ublox_zed-f9p.launch"/>
<include file="$(find ntrip_ros)/launch/ntrip_ros.launch"/>
</launch>
6 changes: 3 additions & 3 deletions common/launch/state_estimation.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<launch>
<include file="$(find common)/launch/gnss.launch"/>
<include file="$(find mpu9250-driver)/launch/mpu9250.launch"/>
</launch>
<include file="$(find common)/launch/raw_data.launch"/>
<include file="$(find robot_localization)/launch/dual_ekf_navsat_example_rob7.launch"/>
</launch>
12 changes: 6 additions & 6 deletions common/launch/tf.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>
<node pkg="tf" type="static_transform_publisher" name="base_link_lidar" args=" 0.36 0 0.19 0 0 0 /base_link /base_link/lidar 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_imu" args=" 0.31 0.11 0.255 0 0 0 /base_link /imu_frame 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_gps" args="-0.11 0 0.59 0 0 0 /base_link /gps 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_camera_front" args=" 0.36 0 0.235 0 0 0 /base_link /base_link/camera_front 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_camera_back" args="-0.12 0 0.22 3.14 0 0 /base_link /base_link/camera_back 100"/>
</launch>
<node pkg="tf" type="static_transform_publisher" name="base_link_lidar" args=" 0.36 0 0.19 0 0 0 /base_link /base_link/lidar 1"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_imu" args=" 0.31 0.11 0.255 0 0 0 /base_link /imu_frame 1"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_gps" args="-0.11 0 0.59 0 0 0 /base_link /gps 1"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_camera_front" args=" 0.36 0 0.235 0 0 0 /base_link /base_link/camera_front 1"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_camera_back" args="-0.12 0 0.22 3.14 0 0 /base_link /base_link/camera_back 1"/>
</launch>
339 changes: 339 additions & 0 deletions common/robot.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,339 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /Grid1/Offset1
- /Axes1
- /filtered_map1
- /filtered_map1/Covariance1/Position1
- /gps_position1/Shape1
- /gps_position1/Covariance1
- /gps_position1/Covariance1/Position1
- /TF1/Frames1
- /Lookahead1/Status1
- /Lookahead1/Namespaces1
Splitter Ratio: 0.538095235824585
Tree Height: 153
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: Front
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 10
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: map
Value: true
- Alpha: 1
Class: rviz/Axes
Enabled: false
Length: 1
Name: Axes
Radius: 0.10000000149011612
Reference Frame: map
Value: false
- Angle Tolerance: 0.10000000149011612
Class: rviz/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: false
Position:
Alpha: 0.30000001192092896
Color: 204; 51; 204
Scale: 1
Value: true
Value: true
Enabled: true
Keep: 300
Name: filtered_map
Position Tolerance: 0.10000000149011612
Queue Size: 10
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Color: 78; 154; 6
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Arrow
Topic: /odometry/filtered_map
Unreliable: false
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: false
Position:
Alpha: 0.30000001192092896
Color: 204; 51; 204
Scale: 1
Value: true
Value: false
Enabled: true
Keep: 100
Name: gps_position
Position Tolerance: 0.10000000149011612
Queue Size: 10
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Color: 52; 101; 164
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Arrow
Topic: /odometry/gps
Unreliable: false
Value: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
base_link/camera_back:
Value: true
base_link/camera_front:
Value: true
base_link/lidar:
Value: true
gps:
Value: true
imu_frame:
Value: true
map:
Value: true
odom:
Value: true
Marker Alpha: 1
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
map:
odom:
base_link:
base_link/camera_back:
{}
base_link/camera_front:
{}
base_link/lidar:
{}
gps:
{}
imu_frame:
{}
Update Interval: 0
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: -999999
Min Color: 0; 0; 0
Min Intensity: 999999
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 5
Size (m): 0.009999999776482582
Style: Points
Topic: /outlier
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: rviz/Marker
Enabled: true
Marker Topic: /controller/lookahead
Name: Lookahead
Namespaces:
"": true
Queue Size: 100
Value: true
- Class: rviz/Image
Enabled: false
Image Topic: /right/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: false
- Class: rviz/Marker
Enabled: true
Marker Topic: /controller/path_visu
Name: Path
Namespaces:
"": true
Queue Size: 100
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /right/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Back
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /left/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Front
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/ThirdPersonFollower
Distance: 12.46381950378418
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.509796142578125
Target Frame: base_link
Yaw: 6.0313401222229
Saved: ~
Window Geometry:
Back:
collapsed: false
Displays:
collapsed: false
Front:
collapsed: false
Height: 1376
Hide Left Dock: false
Hide Right Dock: false
Image:
collapsed: false
QMainWindow State: 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
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 2488
X: 72
Y: 27
Binary file modified odrive_ros/nodes/__pycache__/odrive_interface.cpython-37.pyc
Binary file not shown.
Binary file modified odrive_ros/nodes/__pycache__/odrive_simulator.cpython-37.pyc
Binary file not shown.
2 changes: 1 addition & 1 deletion odrive_ros/nodes/odrive_basic_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ def compute_estimated_twist(self, left_angular_vel, right_angular_vel):
message = TwistWithCovarianceStamped()
left_linear_vel = -1.0*left_angular_vel*self.tyre_circumference
right_linear_vel = right_angular_vel*self.tyre_circumference
angular_vel = (right_linear_vel-left_linear_vel)/self.wheel_track*2.0
angular_vel = (right_linear_vel-left_linear_vel)/self.wheel_track
linear_vel = (left_linear_vel+right_linear_vel)/2.0
message.twist.twist.linear.x = linear_vel
message.twist.twist.angular.z = angular_vel
Expand Down
Loading

0 comments on commit af0fc40

Please sign in to comment.