From f26edd20f607e63a4377f23be5b8069e3bed74a4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 24 Mar 2015 14:50:22 -0700 Subject: Add missing gflags --- Tools/ros/px4_workspace_setup.sh | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) (limited to 'Tools/ros/px4_workspace_setup.sh') diff --git a/Tools/ros/px4_workspace_setup.sh b/Tools/ros/px4_workspace_setup.sh index 3e4bf06a5..1c97ec728 100755 --- a/Tools/ros/px4_workspace_setup.sh +++ b/Tools/ros/px4_workspace_setup.sh @@ -17,14 +17,15 @@ cd .. # mav comm git clone https://github.com/PX4/mav_comm.git +# gflags catkin +git clone https://github.com/ethz-asl/gflags_catkin.git + # glog catkin git clone https://github.com/ethz-asl/glog_catkin.git # catkin simple git clone https://github.com/catkin/catkin_simple.git -# drcsim (for scenery and models) - cd .. catkin_make -- cgit v1.2.3