Skip to content

Commit

Permalink
Merge branch 'dev'
Browse files Browse the repository at this point in the history
  • Loading branch information
GimpelZhang committed Aug 23, 2020
2 parents aee5c8b + 594722d commit 7df54ce
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 22 deletions.
6 changes: 4 additions & 2 deletions ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -941,7 +941,9 @@ sensor_msgs::Imu AirsimROSWrapper::get_imu_msg_from_airsim(const msr::airlib::Im
imu_msg.orientation.y = imu_data.orientation.y();
imu_msg.orientation.z = imu_data.orientation.z();
imu_msg.orientation.w = imu_data.orientation.w();

/*The following imu configs are from the work of xuhao1@github:
(xuhao1/airsim_ros_pkgs)[/https://github.com/xuhao1/airsim_ros_pkgs/blob/master/src/airsim_ros_wrapper.cpp]
corresponding with the vins setting files in the same repo. */
// todo radians per second
imu_msg.angular_velocity.x = (imu_data.angular_velocity.x());
imu_msg.angular_velocity.y = -(imu_data.angular_velocity.y());
Expand All @@ -951,7 +953,7 @@ sensor_msgs::Imu AirsimROSWrapper::get_imu_msg_from_airsim(const msr::airlib::Im
imu_msg.linear_acceleration.x = -imu_data.linear_acceleration.x();
imu_msg.linear_acceleration.y = imu_data.linear_acceleration.y();
imu_msg.linear_acceleration.z = -imu_data.linear_acceleration.z();

// imu_msg.orientation_covariance = ;
// imu_msg.angular_velocity_covariance = ;
// imu_msg.linear_acceleration_covariance = ;
Expand Down
28 changes: 14 additions & 14 deletions ros/src/settings/mynt_stereo_imu_config_720p.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
imu: 1
num_of_cam: 2

imu_topic: "/airsim_car_node/drone_1/imu/Imu"
image0_topic: "/airsim_car_node/drone_1/leftcamera_1/Scene"
image1_topic: "/airsim_car_node/drone_1/rightcamera_1/Scene"
output_path: "../output/"
imu_topic: "/airsim_node/drone_1/imu/Imu"
image0_topic: "/airsim_node/drone_1/leftcamera_1/Scene"
image1_topic: "/airsim_node/drone_1/rightcamera_1/Scene"
output_path: "/media/junchuan/exdisk/catkin_ws/output/"

cam0_calib: "left_pinhole.yaml"
cam1_calib: "right_pinhole.yaml"
Expand All @@ -23,17 +23,17 @@ body_T_cam0: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [1, 0.0, -0.0, -0.06,
0.0, -1, -0.0, 1.6,
-0.0, 0.0, -1, -1.6,
data: [0, 0.0, 1.0, 0,
-1, 0, 0.0, 0.06,
0.0, -1, 0, 2.4,
0., 0., 0., 1.]
body_T_cam1: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [ 1, 0.00, 0.0, 0.06,
0.0, -1, -0.0, 1.6,
0.0, 0.0, -1, -1.6,
data: [ 0, 0.0, 1, 0,
-1, 0, 0.0, -0.06,
0.0, -1, 0, 2.4,
0., 0., 0., 1.]


Expand All @@ -59,9 +59,9 @@ keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#acc_w: 0.5 # accelerometer bias random work noise standard deviation. #0.02
#gyr_w: 0.2 # gyroscope bias random work noise standard deviation. #4.0e-5
acc_n: 0.2 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.05 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.02 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 0.00004 # gyroscope bias random work noise standard deviation. #4.0e-5
gyr_n: 0.5 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.55 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 0.04 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.805 # gravity magnitude

#unsynchronization parameters
Expand All @@ -70,6 +70,6 @@ td: 0.0 # initial value of time offset. unit: s. reade

#loop closure parameters
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
pose_graph_save_path: "../output/" # save and load path
pose_graph_save_path: "/media/junchuan/exdisk/catkin_ws/output/" # save and load path
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0

12 changes: 6 additions & 6 deletions ros/src/settings/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@
"ViewMode": "SpringArmChase",
"PhysicsEngineName": "FastPhysicsEngine",
"ClockType": "SteppableClock",
"ClockSpeed": 1,
"ClockSpeed": 0.34,
"Vehicles": {
"drone_1": {
"VehicleType": "PhysXCar",
"DefaultVehicleState": "Armed",
"EnableCollisionPassthrogh": false,
"EnableCollisions": true,
"EnableCollisionPassthrogh": true,
"EnableCollisions": false,
"AllowAPIAlways": true,
"RC": {
"RemoteControlID": 0,
Expand All @@ -34,7 +34,7 @@
"TargetGamma": 1.5
}
],
"X": 1.6, "Y": -0.06, "Z": -1.6,
"X": 0, "Y": -0.06, "Z": -2.4,
"Pitch": 0, "Roll": 0, "Yaw": 0
},
"rightcamera_1": {
Expand All @@ -47,11 +47,11 @@
"TargetGamma": 1.5
}
],
"X": 1.6, "Y": 0.06, "Z": -1.6,
"X": 0, "Y": 0.06, "Z": -2.4,
"Pitch": 0, "Roll": 0, "Yaw": 0
}
},
"X": 2, "Y": 0, "Z": 0,
"X": 0, "Y": 0, "Z": 0,
"Pitch": 0, "Roll": 0, "Yaw": 0
}
},
Expand Down

0 comments on commit 7df54ce

Please sign in to comment.