Skip to content

Commit fe41668

Browse files
Merge pull request #188 from FS-Online/hotfix
Hotfixes before v1.0.0 release
2 parents b90e0f4 + 135cae6 commit fe41668

File tree

5 files changed

+13
-6
lines changed

5 files changed

+13
-6
lines changed

AirSim/AirLib/include/sensors/imu/ImuSimple.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class ImuSimple : public ImuBase {
5252
const GroundTruth& ground_truth = getGroundTruth();
5353

5454
output.angular_velocity = ground_truth.kinematics->twist.angular;
55-
ground_truth.kinematics->accelerations.linear - Vector3r(0, 0, EarthUtils::Gravity);;
55+
output.linear_acceleration = ground_truth.kinematics->accelerations.linear - Vector3r(0, 0, EarthUtils::Gravity);
5656
output.orientation = ground_truth.kinematics->pose.orientation;
5757

5858
//acceleration is in world frame so transform to body frame

docs/ros-bridge.md

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -101,8 +101,12 @@ Transforms to the ground truth are disabled because this would take away the sta
101101
- `/fsds/ros_bridge/competition_mode` [bool]
102102
Set in: `$(fsds_ros_bridge)/launch/fsds_ros_bridge.launch`
103103
Default: `false`, during competition set to `true`
104-
If competition mode is enabled, the `testing_only` topics won't be available.
105-
Also, input from keyboard and joystick to unreal will no longer controll the vehicle.
104+
If competition mode is enabled, the `testing_only` topics won't be available.
105+
106+
- `/fsds/ros_bridge/manul_mode` [bool]
107+
Set in: `$(fsds_ros_bridge)/launch/fsds_ros_bridge.launch`
108+
Default: `false`
109+
Do not enable vehicle api control. You can controll the car using the keyboard in the simulator.
106110

107111
## Visualization
108112
This package contains some useful launch and config files which will help you in visualizing the data being streamed through the above topics.

ros/src/examples/scripts/sinewave.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#!/usr/bin/env python
22
import rospy, math
3-
from fsds_ros_bridge.msg import ControlCommand
3+
from fs_msgs.msg import ControlCommand
44

55
# the number of seconds to do a full steering cycle (neutral -> full right -> full left -> neutroal)
66
STEERING_PERIOD = 5

ros/src/fsds_ros_bridge/launch/fsds_ros_bridge.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
<arg name="mission_name" default="trackdrive"/>
55
<arg name="track_name" default="A"/>
66
<arg name="competition_mode" default="false"/>
7+
<arg name="manual_mode" default="false"/>
78
<arg name="access_token" default=""/>
89
<arg name="plot" default="false"/>
910
<arg name="rviz" default="false"/>
@@ -24,6 +25,7 @@
2425
<param name="mission_name" type="string" value="$(arg mission_name)"/>
2526
<param name="track_name" type="string" value="$(arg track_name)"/>
2627
<param name="competition_mode" type="bool" value="$(arg competition_mode)" />
28+
<param name="manual_mode" type="bool" value="$(arg manual_mode)" />
2729
<env name="OPERATOR_ACCESS_TOKEN" value="$(arg access_token)"/>
2830
</node>
2931

ros/src/fsds_ros_bridge/src/airsim_ros_wrapper.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -117,15 +117,16 @@ void AirsimROSWrapper::initialize_ros()
117117
double update_imu_every_n_sec;
118118
double update_gss_every_n_sec;
119119
double publish_static_tf_every_n_sec;
120+
bool manual_mode;
120121
nh_private_.getParam("mission_name", mission_name_);
121122
nh_private_.getParam("track_name", track_name_);
122123
nh_private_.getParam("competition_mode", competition_mode_);
124+
nh_private_.getParam("manual_mode", manual_mode);
123125
nh_private_.getParam("update_odom_every_n_sec", update_odom_every_n_sec);
124126
nh_private_.getParam("update_gps_every_n_sec", update_gps_every_n_sec);
125127
nh_private_.getParam("update_imu_every_n_sec", update_imu_every_n_sec);
126128
nh_private_.getParam("update_gss_every_n_sec", update_gss_every_n_sec);
127129
nh_private_.getParam("publish_static_tf_every_n_sec", publish_static_tf_every_n_sec);
128-
129130

130131
create_ros_pubs_from_settings_json();
131132

@@ -141,7 +142,7 @@ void AirsimROSWrapper::initialize_ros()
141142
statistics_timer_ = nh_private_.createTimer(ros::Duration(1), &AirsimROSWrapper::statistics_timer_cb, this);
142143
go_signal_timer_ = nh_private_.createTimer(ros::Duration(1), &AirsimROSWrapper::go_signal_timer_cb, this);
143144

144-
airsim_client_.enableApiControl(competition_mode_, vehicle_name);
145+
airsim_client_.enableApiControl(!manual_mode, vehicle_name);
145146
airsim_client_.armDisarm(true, vehicle_name);
146147

147148
if(!competition_mode_) {

0 commit comments

Comments
 (0)