Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS - All sensors and car support #2743

Merged
merged 36 commits into from
Jul 22, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
36 commits
Select commit Hold shift + click to select a range
661c1be
add PhyXCar
Feb 10, 2020
cd1edc5
script to get the enviroment for passing on to vscode GDB debug session
Feb 10, 2020
f6bda6a
Got car sensor data working with ROS
Feb 11, 2020
d27b156
use static_cast
Feb 12, 2020
bcd8b91
control car via API
Feb 12, 2020
1503943
joystick control for car
Feb 13, 2020
5a4caad
joystick control node and launch file
Feb 13, 2020
1bcd148
Add support for GPS sensor
Feb 13, 2020
8963275
added magnetometer and barometer sensors
Feb 14, 2020
dc94a79
refactor sensors
Feb 14, 2020
a2ec33f
debug
Feb 14, 2020
b99e6eb
add missing package
Feb 17, 2020
59491b2
remove unrelated script
Feb 18, 2020
db474f9
automatic transmission option
Feb 18, 2020
ce9a786
publish car state
Feb 19, 2020
a8a2402
cleanup and add range-distance sensor
Feb 20, 2020
2eb5085
add clock
Feb 20, 2020
5c0d171
clock
Feb 20, 2020
8ebafa6
update clock faster
Feb 20, 2020
f8ecf88
clock
Feb 20, 2020
a894f9c
fix some threading and performance issues
Feb 21, 2020
73c6589
refactor for clock and transforms
Feb 21, 2020
f9eb2d7
launch args, make clock publishing optional, default to false
Feb 26, 2020
fefbf18
clean up comment
Mar 4, 2020
64e913c
Merge branch 'master' into addcar
May 26, 2020
40376d2
working on merge
May 29, 2020
ad81e5a
merge upstream changes
Jun 2, 2020
3312111
remove unrelated script
Jun 2, 2020
0265a6d
Merge branch 'master' into addcar
Jun 2, 2020
86fdd1c
some final cleanup
Jun 2, 2020
e42e154
add tf2_sensor_msgs ros package
Jun 2, 2020
f88432f
removed commented out hector_uav_msgs dependency
Jun 3, 2020
5d54b46
update ROS docs
Jun 3, 2020
8d9c71f
more ros doc updates
Jun 3, 2020
3d64521
add note about ros clock
Jun 3, 2020
33c337d
merge
madratman Jul 22, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 11 additions & 1 deletion AirLib/include/vehicles/car/api/CarApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,16 @@ class CarApiBase : public VehicleApiBase {
kinematics_estimated(kinematics_estimated_val), timestamp(timestamp_val)
{
}

//shortcuts
const Vector3r& getPosition() const
{
return kinematics_estimated.pose.position;
}
const Quaternionr& getOrientation() const
{
return kinematics_estimated.pose.orientation;
}
};

public:
Expand Down Expand Up @@ -151,4 +161,4 @@ class CarApiBase : public VehicleApiBase {


}} //namespace
#endif
#endif
48 changes: 42 additions & 6 deletions docs/airsim_ros_pkgs.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,11 @@ Verify version by `gcc --version`

- Ubuntu 16.04
* Install [ROS kinetic](https://wiki.ros.org/kinetic/Installation/Ubuntu)
* Install mavros packages: `sudo apt-get install ros-kinetic-mavros*`
* Install tf2 sensor and mavros packages: `sudo apt-get install ros-kinetic-tf2-sensor-msgs ros-kinetic-mavros*`

- Ubuntu 18.04
* Install [ROS melodic](https://wiki.ros.org/melodic/Installation/Ubuntu)
* Install mavros packages: `sudo apt-get install ros-melodic-mavros*`
* Install tf2 sensor and mavros packages: `sudo apt-get install ros-melodic-tf2-sensor-msgs ros-melodic-mavros*`

- Install [catkin_tools](https://catkin-tools.readthedocs.io/en/latest/installing.html)
`sudo apt-get install python-catkin-tools` or
Expand Down Expand Up @@ -60,7 +60,7 @@ GPS coordinates corresponding to global NED frame. This is set in the airsim's [
This the current GPS coordinates of the drone in airsim.

- `/airsim_node/VEHICLE_NAME/odom_local_ned` [nav_msgs/Odometry](https://docs.ros.org/api/nav_msgs/html/msg/Odometry.html)
Odometry in NED frame wrt take-off point.
Odometry in NED frame (default name: odom_local_ned, launch name and frame type are configurable) wrt take-off point.

- `/airsim_node/VEHICLE_NAME/CAMERA_NAME/IMAGE_TYPE/camera_info` [sensor_msgs/CameraInfo](https://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html)

Expand All @@ -69,6 +69,19 @@ Odometry in NED frame wrt take-off point.

- `/tf` [tf2_msgs/TFMessage](https://docs.ros.org/api/tf2_msgs/html/msg/TFMessage.html)

- `/airsim_node/VEHICLE_NAME/altimeter/SENSOR_NAME` [airsim_ros_pkgs::Altimeter] This the current altimeter reading for altitude, pressure, and QNH (https://en.wikipedia.org/wiki/QNH)

- `/airsim_node/VEHICLE_NAME/imu/SENSOR_NAME` [sensor_msgs::Imu] (http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html)
IMU sensor data

- `/airsim_node/VEHICLE_NAME/magnetometer/SENSOR_NAME` [sensor_msgs::MagneticField] (http://docs.ros.org/api/sensor_msgs/html/msg/MagneticField.html)
Meausrement of magnetic field vector/compass

- `/airsim_node/VEHICLE_NAME/distance/SENSOR_NAME` [sensor_msgs::Range] (http://docs.ros.org/api/sensor_msgs/html/msg/Range.html)
Meausrement of distance from an active ranger, such as infrared or IR

- `/airsim_node/VEHICLE_NAME/lidar/SENSOR_NAME` [sensor_msgs::PointCloud2] (http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html)
LIDAR pointcloud

#### Subscribers:
- `/airsim_node/vel_cmd_body_frame` [airsim_ros_pkgs/VelCmd](https://github.com/microsoft/AirSim/tree/master/ros/src/airsim_ros_pkgs/msg/VelCmd.msg)
Expand All @@ -83,6 +96,9 @@ Odometry in NED frame wrt take-off point.
- `/gimbal_angle_quat_cmd` [airsim_ros_pkgs/GimbalAngleQuatCmd](https://github.com/microsoft/AirSim/tree/master/ros/src/airsim_ros_pkgs/msg/GimbalAngleQuatCmd.msg)
Gimbal set point in quaternion.

- `/airsim_node/VEHICLE_NAME/car_cmd` [airsim_ros_pkgs/CarControls]
Throttle, brake, steering and gear selections for control. Both automatic and manual transmission control possible, see the car_joy.py script for use.

#### Services:
- `/airsim_node/VEHICLE_NAME/land` [airsim_ros_pkgs/Takeoff](https://docs.ros.org/api/std_srvs/html/srv/Empty.html)

Expand All @@ -92,20 +108,40 @@ Odometry in NED frame wrt take-off point.
Resets *all* drones

#### Parameters:
- `/airsim_node/world_frame_id` [string]
Set in: `$(airsim_ros_pkgs)/launch/airsim_node.launch`
Default: world_ned
Set to "world_enu" to switch to ENU frames automatically

- `/airsim_node/odom_frame_id` [string]
Set in: `$(airsim_ros_pkgs)/launch/airsim_node.launch`
Default: odom_local_ned
If you set world_frame_id to "world_enu", the default odom name will instead default to "odom_local_enu"

- `/airsim_node/coordinate_system_enu` [boolean]
Set in: `$(airsim_ros_pkgs)/launch/airsim_node.launch`
Default: false
If you set world_frame_id to "world_enu", this setting will instead default to true

- `/airsim_node/update_airsim_control_every_n_sec` [double]
Set in: `$(airsim_ros_pkgs)/launch/airsim_node.launch`
Default: 0.01 seconds.
Default: 0.01 seconds.
Timer callback frequency for updating drone odom and state from airsim, and sending in control commands.
The current RPClib interface to unreal engine maxes out at 50 Hz.
Timer callbacks in ROS run at maximum rate possible, so it's best to not touch this parameter.
Timer callbacks in ROS run at maximum rate possible, so it's best to not touch this parameter.

- `/airsim_node/update_airsim_img_response_every_n_sec` [double]
Set in: `$(airsim_ros_pkgs)/launch/airsim_node.launch`
Default: 0.01 seconds.
Default: 0.01 seconds.
Timer callback frequency for receiving images from all cameras in airsim.
The speed will depend on number of images requested and their resolution.
Timer callbacks in ROS run at maximum rate possible, so it's best to not touch this parameter.

- `/airsim_node/publish_clock` [double]
Set in: `$(airsim_ros_pkgs)/launch/airsim_node.launch`
Default: false
Will publish the ros /clock topic if set to true.

### Simple PID Position Controller Node

#### Parameters:
Expand Down
8 changes: 8 additions & 0 deletions ros/src/airsim_ros_pkgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,12 @@ find_package(catkin REQUIRED COMPONENTS
rospy
sensor_msgs
std_msgs
geographic_msgs
geometry_msgs
std_srvs
tf2
tf2_ros
tf2_sensor_msgs
)

add_message_files(
Expand All @@ -46,6 +49,10 @@ add_message_files(
GPSYaw.msg
VelCmd.msg
VelCmdGroup.msg
CarControls.msg
CarState.msg
Altimeter.msg
Environment.msg
)

add_service_files(
Expand All @@ -63,6 +70,7 @@ generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
geographic_msgs
)

catkin_package(
Expand Down
Loading