Skip to content

Commit

Permalink
Merge pull request #9 from carla-simulator/feature/ackermann_drive
Browse files Browse the repository at this point in the history
Feature/ackermann drive
  • Loading branch information
fabianoboril committed Dec 18, 2018
2 parents 4d125d5 + 8b74f0e commit 85ac33c
Show file tree
Hide file tree
Showing 18 changed files with 2,136 additions and 45 deletions.
13 changes: 11 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,22 +6,31 @@ find_package(catkin REQUIRED COMPONENTS
rospy
sensor_msgs
tf
dynamic_reconfigure
)

catkin_python_setup()

add_message_files(
FILES
CarlaVehicleControl.msg
EgoVehicleControlCurrent.msg
EgoVehicleControlInfo.msg
EgoVehicleControlMaxima.msg
EgoVehicleControlState.msg
EgoVehicleControlTarget.msg
)

generate_messages(
DEPENDENCIES
sensor_msgs
std_msgs
)

catkin_package()
generate_dynamic_reconfigure_options(
config/EgoVehicleControlParameter.cfg
)

catkin_package()


include_directories(
Expand Down
4 changes: 4 additions & 0 deletions client_with_rqt.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<include file="$(find carla_ros_bridge)/client.launch" pass_all_args="True"/>
<node pkg="rqt_gui" type="rqt_gui" name="rqt_gui" args="--perspective-file $(find carla_ros_bridge)/config/EgoVehicleControlInfo.perspective"/>
</launch>
Loading

0 comments on commit 85ac33c

Please sign in to comment.