GithubHelp home page GithubHelp logo

autorally / autorally Goto Github PK

View Code? Open in Web Editor NEW
721.0 82.0 228.0 33.1 MB

Software for the AutoRally platform

Home Page: http://autorally.github.io

CMake 2.60% C++ 72.03% Python 8.88% Shell 0.78% Cuda 15.32% C 0.39%
autonomous-driving autonomous-vehicles robotics ros

autorally's Introduction

AutoRally

alt text

Software for the AutoRally research platform.

AutoRally Platform Website

AutoRally Youtube Channel

Platform Paper

BibTex:

@article{goldfain2019autorally,
  title={AutoRally: An Open Platform for Aggressive Autonomous Driving},
  author={Goldfain, Brian and Drews, Paul and You, Changxi and Barulic, Matthew and Velev, Orlin and Tsiotras, Panagiotis and Rehg, James M},
  journal={IEEE Control Systems Magazine},
  volume={39},
  number={1},
  pages={26--55},
  year={2019},
  publisher={IEEE}
}

Contributing

We welcome bug fixes, ehancements, new features, and feedback!

Please submit pull requests to the melodic-devel branch that conform to the ROS C++ Style Guide. We use Gitflow, so master branch is reserved for releases.

Setup Instructions

Contents

  1. Install Prerequisites
  2. Clone repository
  3. Install AutoRally ROS Dependencies
  4. Compilation/Running
  5. Generate Documentation
  6. Test Setup in Simulation
  7. Autonomous Driving in Simulation

1. Install Prerequisites

  1. Install Ubuntu 18.04 64-bit

  2. Install required packages

    sudo apt install git doxygen openssh-server libusb-dev texinfo

    ROS Melodic only supports Python 2.7. Before installing Python packages, you need to ensure that python points to Python 2.7, e.g., by setting up a Python 2.7 conda environment:

    conda create -n my_ros_env python=2.7
    source activate my_ros_env
    conda install defusedxml
    conda install -c jdh88 rospkg
    

    The following tools are recommended, but not required for this project.

    • cutecom
    • cmake-curses-gui
    • synaptic
    • python-termcolor

    sudo apt install cutecom cmake-curses-gui synaptic python-termcolor

  3. Install ros-melodic-desktop-full

  4. Install MPPI Dependencies (if you have a GPU and will run MPPI)

    The core idea behind MPPI is to sample thousands of trajectories really fast. This is accomplished by implementing the sampling step on a GPU, for which you will need CUDA. We also use an external library to load python's numpy zip archives (.npz files) into C++.

  5. Install gtsam

    Follow the gtsam Quick Start guide to clone and install the develop branch of gtsam.

    Instead of cmake .., use:

    cmake -DGTSAM_INSTALL_GEOGRAPHICLIB=ON -DGTSAM_WITH_EIGEN_MKL=OFF ..

    Once install is complete, make sure linux can see the shared library:

    sudo ldconfig

  6. Update to latest version of gazebo 9.XX

    You will want to be on the latest version of gazebo 9.

2. Clone or Fork Repositories

Get the autorally repository in a catkin workspace. The suggested location is ~/catkin_ws/src/, but any valid catkin worskspace source folder will work. We suggest forking over cloning if you will be working with the code.

Also clone the IMU code and Pointgrey camera drivers into the same catkin workspace:

git clone https://github.com/AutoRally/imu_3dm_gx4.git
git clone https://github.com/ros-drivers/pointgrey_camera_driver.git

3. Build Pointgrey Camera Driver

Since there are no pre-built drivers for Melodic, follow these instructions to build the driver yourself.

  • The SDK can be downloaded here. The file to download is flycapture2-2.13.3.31-amd64-pkg_Ubuntu18.04.tgz.
  • You may need to run sudo apt --fix-broken install after installing the suggested packages and before running sudo sh install_flycapture.sh.

4. Install AutoRally ROS Dependencies

Within the catkin workspace folder, run this command to install the packages this project depends on.

rosdep install --from-path src --ignore-src -y

5. Compilation & Running

First, check your Eigen version with pkg-config --modversion eigen3. If you don't have at least version 3.3.5, upgrade Eigen by following "Method 2" within the included INSTALL file.

Then, to compile and install, run catkin_make from the catkin workspace folder. If your version of CUDA does not support gcc-7, you may need to use

catkin_make -DCMAKE_C_COMPILER=gcc-6 -DCMAKE_CXX_COMPILER=g++-6

Due to the additional requirement of ROS's distributed launch system, you must run

source src/autorally/autorally_util/setupEnvLocal.sh

before using any AutoRally components. See the wiki for more information about how to set this system up for distributed launches on your vehicle platform.

Note: If you are unfamiliar with catkin, please know that you must run source catkin_ws/devel/setup.sh before ROS will be able to locate the autorally packages (and thus you must run this before sourcing setupEnvLocal.sh). This line can be added to your ~/.bashrc file so that it is automatically run on opening a terminal.

6. Generate Documentation

You can generate or update code documentation by running doxygen in autorally/.

To view code documentation open autorally/doc/html/index.html in a web browser.

7. Start the AutoRally Simulation to Test Configuration

roslaunch autorally_gazebo autoRallyTrackGazeboSim.launch

You can use a USB gamepad to drive the simulated platform around. On startup, the runstop message published by the joystick node is false. Press any of the buttons by the right stick (normally labelled X, Y, A, B or square, triangle, X, circle) to toggle the published value.

Verify runstop motion is enabled by looking at the runstopMotionEnabled field in the /chassisState topic (rostopic echo /chassisState).

If you aren't using a gamepad, you will have to configure another source of runstop information for the platform to move:

  • Comment out the line <include file="$(find autorally_control)/launch/joystickController.launch" /> near the end of autorally_gazebo/launch/autoRallyTrackGazeboSim.launch

  • rosrun rqt_publisher rqt_publisher

and configure rqt_publisher to publish a message to topic /runstop of type autorally_msgs/runstop at 1 Hz with sender set to rqt_publisher and motionEnabled set to true.

  • Verify that runstopMotionEnabled is true in /chassisState topic.

8. Autonomous Driving in Simulation

At the end of this section the robot will be driving autonomously in simulation using controllers available in autorally_control.

Position the robot in the same spot as when the simulation starts and make sure runstop motion should is enabled (set to true).

Start waypoint follower:

roslaunch autorally_control waypointFollower.launch

Start constant speed controller and tell it what speed to drive:

roslaunch autorally_control constantSpeedController.launch
rosrun rqt_publisher rqt_publisher

Configure a publisher on topic constantSpeedController/speedCommand of type std_msgs/Float64 at rate 10 with value of 3 (you can adjust he value once everything is running). The value is the target velocity in m/s, and as soon as you do this the platform should move if motion is enabled.

If the robot turns and hits the barrier it's probably because the state estimator has not converged, so its orientation estimate is incorrect. Just select the track barriers and move them up to allow the robot to continue driving, and the estimator should converge and the vehicle will return to within the barriers.

What's Next

More detailed explanations of the controllers and state estimator can be found on the wiki:

Controlling the AutoRally platform is a tutorial for how your own controller can control the AutoRally platform (in simulation or on hardware).

Running Vehicles in Simulation is a tutorial on how run gazebo in the two different worlds and with multiple vehicles.

If you are configuring a physical AutoRally platform, the next step is to configure the compute box, all of the peripherals, and the launch system. Those instructions are found in the Platform Configuration Instructions.

autorally's People

Contributors

aminer7 avatar aravindbattaje avatar autorally-gatech avatar barulicm avatar bgoldfai avatar dpattison3 avatar ebretl avatar eyildirir avatar gradyrw avatar ivandariojr avatar jasongibson274 avatar jisacks avatar jzheng84 avatar kamilsaigol avatar kphawkins avatar nhatch avatar nolanwagener avatar orlinv avatar pdrews avatar scalpel78 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

autorally's Issues

Simulation Instructions / Tutorial

I think there is a need to have instructions on how to run the system in Gazebo.
I can run the simulator after installing as per the document, but its not clear on how to launch the rest of the system to run in simulation mode.

I tried to launch the autorally_platform but there are too many dependencies on physical hardware and the simulation does not work.

Is there a simulation tutorial somewhere?
Thanks

gazebo errors

Hi, thanks for the open-source code!

It has the following errors after $roslaunch autorally_gazebo autoRallyTrackGazeboSim.launch

Error [Server.cc:345] Unregistered physics engine [dart], the default will be used instead.

Msg Connected to gazebo master @ http://127.0.0.1:11345
Msg Publicized address: 206.87.212.231
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]
Error [Connection.hh:264] Header is empty
Error [Master.cc:124] Master got empty data message from[45889]

Teensy LC Issues on Ubuntu 18

Hello,

We are trying to setup our AutoRally (platform v1.4) on Ubuntu 18/Melodic, and we are currently running into an issue where the Teensy LC that controls our runstop box cannot communicate with any of our machines running Ubuntu 18. When it is plugged in, it shows up as 'arRunStop' in the /dev/ folder as it should, but the autorally_core RunStop node does not get any messages from it. The Arduino IDE is not able to read its messages from the serial monitor, nor can Cutecom. The Arduino IDE is also not able to upload code to it. However, it works fine on our Ubuntu 16 machines (RunStop node gets messages from it, Arduino Serial Monitor can read its messages, and Arduino IDE can upload code to it).

Do you have any ideas why we might be running into this issue?

Where can I find the parameters of car's dynamic?

Hi,
I am so exited I can run the platform, this is the first plantform I can run since I start to learn ros. I am trying to implant a pure pursuit tracking controller, it shuold be very simple. But I need some car's parameters. And also, I want to further extend the motion planning to this platform, while it should be a big challenge for me because of my weak knowledge of ros, I will keep trying.
-shan

Compilation error of path integral CUDA files

I am running into the following error when running catkin_make for the autorally package:

CMake Error at path_integral_bf_generated_path_integral_main.cu.o.Release.cmake:215 (message):
  Error generating
  /home/nolan/catkin_ws/build/autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir//./path_integral_bf_generated_path_integral_main.cu.o


autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/build.make:63: recipe for target 'autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/path_integral_bf_generated_path_integral_main.cu.o' failed
make[2]: *** [autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/path_integral_bf_generated_path_integral_main.cu.o] Error 1
CMakeFiles/Makefile2:7553: recipe for target 'autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/all' failed
make[1]: *** [autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
CMake Error at path_integral_nn_generated_path_integral_main.cu.o.Release.cmake:215 (message):
  Error generating
  /home/nolan/catkin_ws/build/autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_nn.dir//./path_integral_nn_generated_path_integral_main.cu.o


autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_nn.dir/build.make:70: recipe for target 'autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_nn.dir/path_integral_nn_generated_path_integral_main.cu.o' failed
make[2]: *** [autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_nn.dir/path_integral_nn_generated_path_integral_main.cu.o] Error 1
make[2]: *** Waiting for unfinished jobs....
CMake Error at path_integral_bf_generated_path_integral_main.cu.o.Release.cmake:215 (message):
  Error generating
  /home/nolan/catkin_ws/build/autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir//./path_integral_bf_generated_path_integral_main.cu.o


autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_nn.dir/build.make:63: recipe for target 'autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/path_integral_bf_generated_path_integral_main.cu.o' failed
make[2]: *** [autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/path_integral_bf_generated_path_integral_main.cu.o] Error 1
CMakeFiles/Makefile2:7634: recipe for target 'autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_nn.dir/all' failed
make[1]: *** [autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_nn.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2

This same error appears whether I am in a conda environment (using either cmake 3.5.0 or 3.12.0) or outside of a conda environment (using cmake 3.5.2).

Controller Spawner couldn't find the expected controller_manager ROS interface

Hello I installed your repo and trying to run the roslaunch autorally_gazebo autoRallyTrackGazeboSim.launch and this warn appears:

Screenshot from 2019-03-29 12-05-39

[WARN] [1553860760.215555, 0.000000]: Controller Spawner couldn't find the expected controller_manager ROS interface.
[controller_spawner-6] process has finished cleanly
log file: /home/daniel/.ros/log/03184c32-521a-11e9-af93-1831bf747ba9/controller_spawner-6*.log
[spawn_platform-5] process has finished cleanly
log file: /home/daniel/.ros/log/03184c32-521a-11e9-af93-1831bf747ba9/spawn_platform-5*.log

Do you know how to fix this, because I'm being able to get anything in any simulation to work. thx.

Car steers only to one side when learning dynamics

Hello,

I'm trying to learn the parameters of the car by myself. The inputs, outputs and neural network architecture are exactly the same as it is in the repository and in the paper. The data I have collected is from 60 minutes of various driving in a simulation.

I'm using PyTorch to train the network and get mean total errors between 0.2 to 0.3. When I plug the dynamics in the simulation again, the trajectory planned looks correct, however, the car steers heavily to one side (left) and fails to follow the trajectory. Then it realises it has missed it and just reverses to attempt it again and repeat..

Missing chassisCommandPriorities config

Autorally Gazebo launch file autoRallyTrackGazeboSim.launch calls for chassisCommandPriorities.yaml on line 89:
<rosparam param="chassisCommandProirities" command="load" file="$(env AR_CONFIG_PATH)/chassisCommandPriorities.yaml" />

However the file doesn't exist. The following error appears in the terminal:
error loading <rosparam> tag: file does not exist [/home/zzz/catkin_ws/src/autorally/autorally_util/config/chassisCommandPriorities.yaml] XML is <rosparam command="load" file="$(env AR_CONFIG_PATH)/chassisCommandPriorities.yaml" param="chassisCommandProirities"/> The traceback for the exception was written to the log file

ROS2 GAZEBO99 - Robot keeps jerking and moving

I'm from Nigeria, so I'm trying to set up a simulation for a local autonomous rc car group
I coming up next year.

I'm trying to run autorally uising ros2 and gazebo 9, I was able to build descrption and gazebo package. But when I launch the robot into rviz2 and gazebo, the robots krrps jerking and moving slowly on its own without any commands been sent to joint states topic. Also Whem I send command to joint states topic only the robot in rviz2 receives it but in gazebo it's just jerking and moving.

Any help please

Screencast from 12-28-2019 11:02:06 AM.zip

Unused parameter `state` passed in `enforceConstraints` function of `template NeuralNetModel`

In autorally/autorally_control/include/autorally_control/path_integral/neural_net_model.cut

Lines 245 - 253, the MatrixXf &state is passed as a parameter to a function, but it's not used... How come? Thank you!

template<int S_DIM, int C_DIM, int K_DIM, int... layer_args>
void NeuralNetModel<S_DIM, C_DIM, K_DIM, layer_args...>::enforceConstraints(Eigen::MatrixXf &state, Eigen::MatrixXf &control)
{
  int i;
  for (i = 0; i < CONTROL_DIM; i++){
    if (control(i) < control_rngs_[i].x){
      control(i) = control_rngs_[i].x;
    }
    else if (control(i) > control_rngs_[i].y){
      control(i) = control_rngs_[i].y;
    }
  }
}

Camera Triggering Problems

Camera frame rate does not match trigger frequency

While the Arduino is triggering at 40 FPS, the cameras are only outputting at 20 FPS. Removing the GPIO cable prevents the camera from returning any images at all, so triggering is working on some level.

Explanation of the DDP optimization

Hi,

Are there any explanation (paper, post or something else) of using DDP optimization after the MPPI control iteration?

I would be very appreciated for any comments about the advantages and disadvantages of using DDP.

Fix warnings on startup of simulation Kinetic/16.04

with command: roslaunch autorally_gazebo autoRallyTrackGazeboSim.launch

I get the warnings:
xacro: Traditional processing is deprecated. Switch to --inorder processing!
To check for compatibility of your document, use option --check-order.
For more infos, see http://wiki.ros.org/xacro#Processing_Order

[ WARN] [1522162655.208077500, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'left_front_shock'.
[ WARN] [1522162655.208968185, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'left_steering_joint'.
[ WARN] [1522162655.209475722, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'left_front_axle'.
[ WARN] [1522162655.210048559, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'right_front_shock'.
[ WARN] [1522162655.210506718, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'right_steering_joint'.
[ WARN] [1522162655.210996375, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'right_front_axle'.
[ WARN] [1522162655.211465079, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'left_rear_shock'.
[ WARN] [1522162655.211928406, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'left_rear_axle'.
[ WARN] [1522162655.212379022, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'right_rear_shock'.
[ WARN] [1522162655.212832012, 0.001000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'right_rear_axle'.

and a little while after the simulation has been running:
[ WARN] [1522162656.539863898, 1.000000000]: diagnostic_updater: No HW_ID was set. This is probably a bug. Please report it. For devices that do not have a HW_ID, set this value to 'none'. This warning only occurs once all diagnostics are OK so it is okay to wait until the device is open before calling setHardwareID.

[kinetic-devel] Segmentation Fault When Launching Gazebo Simulator

I'm trying to run the Gazebo simulator after a fresh install and getting a crash every time:

[ WARN] [1518055560.114620641, 0.034000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the <hardwareInterface> tag in joint 'right_rear_axle'.
[ INFO] [1518055560.177734688, 0.034000000]: Loaded gazebo_ros_control.
[autorally_platform/spawn_platform-4] process has finished cleanly
log file: /home/kelsey/.ros/log/8d986cc0-0c61-11e8-a754-309c230ef122/autorally_platform-spawn_platform-4*.log
[WARN] [1518055560.347148, 0.034000]: The specified list of shock absorbers is invalid. No shock absorbers will be used.
[WARN] [1518055560.349486, 0.034000]: The specified namespace value is invalid. The default timeout value will be used instead.
Segmentation fault (core dumped)
[autorally_platform/gazebo-2] process has died [pid 20555, exit code 139, cmd /opt/ros/kinetic/lib/gazebo_ros/gzserver -e dart urdf/populated_AR.world /autorally_platform/camera/left:=/left_camera /autorally_platform/camera/right:=/right_camera __name:=gazebo __log:=/home/kelsey/.ros/log/8d986cc0-0c61-11e8-a754-309c230ef122/autorally_platform-gazebo-2.log].
log file: /home/kelsey/.ros/log/8d986cc0-0c61-11e8-a754-309c230ef122/autorally_platform-gazebo-2*.log

Gazebo works fine when launching independently so I don't believe it's a graphics card/driver issue. I believe it happens when starting the gazebo server and might be related to an invalid URDF model.

Ubuntu 16.04
ROS Kinetic
Gazebo 7.9.0
Branch: kinetic-devel

Compilation dependency issues

I had some issues getting autorally to build, here is how I got around those issues.

I'm runniung ubuntu 16.04 and using ros kinetic as the README instructs.

apt dependencies

  • I needed to also install libgeographic-dev

Dependencies outside of apt:

rosdep dependency issues

Pointgrey got bought by flir and some links broke, so a few dependencies stopped being able to be built: ros-drivers/pointgrey_camera_driver#187
I got around that by installing old snapshot builds for ros-kinetic-flir-camera-driver, ros-kinetic-pointgrey-camera-driver, and ros-kinetic-spinnaker-camera-driver.

GTSAM

While compiling GTSAM I had to add -DGTSAM_USE_SYSTEM_EIGEN=ON to the cmake command as GTSAM packages it's own version of the Eigen lib.

Library issues

autorally_core/src/StateEstimator/CMakeLists.txt asks for /usr/local/lib/libgtsam.so, while gtsam provided /usr/local/lib/libgtsam.so.4.0.2 and /usr/local/lib/libgtsam.so.4
I changed the CMakeLists.txt to ask for libgtsam.so and ran sudo ln -s /usr/local/lib/libgtsam.so.4.0.2 /usr/local/lib/libgtsam.so

The StateEstimator CMakeLists.txt also asks for /usr/local/lib/libGeographic.so, and libgeographic-dev put it at /usr/lib/x86_64-linux-gnu/libGeographic.so, so I changed it to ask for libGeographic.so
Diff:

diff --git a/autorally_core/src/StateEstimator/CMakeLists.txt b/autorally_core/src/StateEstimator/CMakeLists.txt
index 40b35ae..4249327 100644
--- a/autorally_core/src/StateEstimator/CMakeLists.txt
+++ b/autorally_core/src/StateEstimator/CMakeLists.txt
@@ -9,7 +9,7 @@ if(GTSAM_FOUND)
   include_directories(include ${catkin_INCLUDE_DIRS} "/usr/local/include")
 
   add_executable(StateEstimator StateEstimator.cpp)
-  target_link_libraries(StateEstimator ${catkin_LIBRARIES} ${ROS_LIBRARIES} /usr/local/lib/libgtsam.so /usr/local/lib/libGeographic.so ${TBB_LIBRARIES} ar_diagnostics)
+  target_link_libraries(StateEstimator ${catkin_LIBRARIES} ${ROS_LIBRARIES} libgtsam.so libGeographic.so ${TBB_LIBRARIES} ar_diagnostics)
   add_dependencies(StateEstimator autorally_msgs_gencpp)
 
   install(TARGETS StateEstimator

catkin workspaces

This was just an issue with me not knowing how catkin workspaces work, but I think at least some parts of the following would make the Clone or Fork Repositories section of the README more clear:

mkdir -p $HOME/catkin_ws/src
cd $HOME/catkin_ws/src
catkin_init_workspace
cd $HOME/catkin_ws
catkin_make
cd $HOME/catkin_ws/src
git clone https://github.com/AutoRally/imu_3dm_gx4.git
git clone https://github.com/AutoRally/autorally.git

At this point it builds, but I can't test much as gazbebo is has libGL errors and then segfaults.

Chassis controller for chassis version 1.0+

Also comes with updated massages. The current interface to the chassis via the servoInterface nodelet and arduinoOnboard is:

autorally_msgs::safeSpeed->servoInterface
autorally_msgs::servoCommand->servoInterface
arduinoOnboard->autorally_msgs::wheelSpeeds
arduinoOnboard->autorally_msgs::servoCommand RC signals read from receiver

The redesigned interface to the new autorally_chassis nodelet will be:

autorally_msgs::chassisCommand->autorally_chassis to control actuators
autorally_msgs::runstop->autorally_chassis for software runstop messages
autorally_chassis->autorally_msgs::chassisState for chassis state including commanded values, who is commanding each actuator, and feedback from ESC
autorally_chassis->autorally_msgs::wheelSpeeds
autorally_chassis->autorally_msgs::chassisCommand for RC signals read from receiver

This is a results of a new, more integrated electronics box design and enhanced feedback with the new ESC.

cuda related compile error

Basically followed the installations instructions, but got the following error. Some variables in the .cu files seems not to be defined.

[ 96%] Building NVCC (Device) object autorally/autorally_control/src/path_integral/CMakeFiles/path_integral_bf.dir/path_integral_bf_generated_path_integral_main.cu.o
/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(81): error: identifier "DynamicsModel" is undefined

/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(81): error: identifier "MPPI_NUM_ROLLOUTS__" is undefined

/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(81): error: identifier "BLOCKSIZE_X" is undefined

/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(81): error: identifier "BLOCKSIZE_Y" is undefined

/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(97): error: identifier "DynamicsModel" is undefined

/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(97): error: identifier "model" is undefined

/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(97): error: expected a type specifier

/home/yf/autorally_ws/src/autorally/autorally_control/include/autorally_control/path_integral/mppi_controller.cuh(56): error: name followed by "::" must be a class or namespace name
          detected during instantiation of class "autorally_control::MPPIController<DYNAMICS_T, COSTS_T, ROLLOUTS, BDIM_X, BDIM_Y> [with DYNAMICS_T=<error-type>, COSTS_T=autorally_control::MPPICosts, ROLLOUTS=<error-constant>, BDIM_X=<error-constant>, BDIM_Y=<error-constant>]" 
/home/yf/autorally_ws/src/autorally/autorally_control/src/path_integral/path_integral_main.cu(103): here

IMU orientation transform

Verify/fix the transform from the IMU internal navigation frame (published on /imu/filter) to the state estimator navigation frame. This issue may be caused by a poorly calibrated magnetometer inside the IMU, or a problem with the transform. More investigation is needed to determine.

MPPI controller information

Hi!
Do you plan to share the MPPI controller code (mppi_controller)? Where can I find the information/theory about it?

ROS simulation not starting

Hi, i am new to ROS but i did the setup accordingly on a vmware 1404 client.

on the last roslaunch simulation, it was not successful:

... logging to /home/desk/.ros/log/a2cc5d5a-1eaf-11e6-9179-000c29410603/roslaunch-ubuntu-41202.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

error loading tag:
file does not exist [/config//servoCommandPriorities.yaml]
XML is
The traceback for the exception was written to the log file

could you please help me with this, thanks.

AutoRally A-star Path Finding

I am trying to setup the ROS Navigation Stack with autorally platform.
I was able to put a laser on the robot in Gazebo and was able to get the laser data in RViz.
The problem is I am not able to get the map. Also, even though robot moves in Gazebo but it is not moving in Rviz. It looks like only its wheels are moving. I tried writing a node to get tf between map and base_link but apparently a new tf tree is being created. Even the static_transform_publisher isn't working for map(worked for hokuyo laser). Can anyone suggest how to setup Navigation Stack?
Also, I am not able to setup WayPoint Controller. How to visualize the waypoints in Rviz?
One more doubt is which is line 93 in autorally_gazebo/launch/autoRallyTrackGazeboSim.launch that I need to comment? Please let me know if you need any other details

Build Components and Prices

Hi,
I was going through the excel sheet with all components and their prices.
I have a few questions about the parts.

Some of the parts are quite expensive. For example the IMU, GPS and even the chassis.
Were there any considerations given to cheaper options and if so it would help to know why cheaper options were not considered.

Additionally, it is not clear how cameras are being utilised in the control process. Are they used for obstacle avoidance?

If there were not cameras involved, would it be possible eliminate the onboard compute-box and use wireless commands?

chassisState not published without control input

When I do not use a joystick and instead attempt to manually set runstopMotionEnabled by publishing to runstop topic with the rqt_publisher or a Python script, I found that chassisState was not being published by the simulator. Instead I get the following warning:

WARNING: no messages received and simulated time is active.
Is /clock being published?

However, when I enable runstopMotionEnabled from the AutoRally OCS and set the control from the Control tab, I can then do a rostopic echo /chassisState successfully. There are no issues when I use the joystick. It seems that the simulator does not publish chassisState unless it receives control decisions.

catkin_make出错 Catkin_make error with Ubuntu 16.04.4

I use Ubuntu 16.04.4 cuda-8.0

usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
autorally/autorally_core/src/ocs/CMakeFiles/ocs.dir/build.make:88: recipe for target 'autorally/autorally_core/src/ocs/moc_qnode.cxx' failed
make[2]: *** [autorally/autorally_core/src/ocs/moc_qnode.cxx] Error 1
CMakeFiles/Makefile2:5208: recipe for target 'autorally/autorally_core/src/ocs/CMakeFiles/ocs.dir/all' failed
make[1]: *** [autorally/autorally_core/src/ocs/CMakeFiles/ocs.dir/all] Error 2
make[1]: *** 正在等待未完成的任务....
[ 59%] Building CXX object autorally/autorally_core/src/SerialSensorInterface/CMakeFiles/SerialSensorInterface.dir/SerialInterfaceThreaded.cpp.o
[ 59%] Built target driver_base_generate_messages_eus
[ 59%] Building CXX object autorally/autorally_core/src/SerialSensorInterface/CMakeFiles/SerialSensorInterface.dir/SerialCommon.cpp.o
[ 59%] Built target autorally_msgs_generate_messages_eus
[ 60%] Building CXX object imu_3dm_gx4/CMakeFiles/imu_3dm_gx4.dir/src/imu.cpp.o
[ 61%] Linking CXX shared library /home/launchx-mask/catkin_ws/devel/lib/libRingBuffer.so
[ 61%] Built target RingBuffer
[ 62%] Linking CXX shared library /home/launchx-mask/catkin_ws/devel/lib/libSerialSensorInterface.so
[ 62%] Built target SerialSensorInterface
[ 63%] Linking CXX shared library /home/launchx-mask/catkin_ws/devel/lib/libImageRepublisher.so
[ 63%] Linking CXX shared library /home/launchx-mask/catkin_ws/devel/lib/libDiagnostics.so
[ 63%] Built target Diagnostics
[ 63%] Built target ImageRepublisher
[ 63%] Linking CXX executable /home/launchx-mask/catkin_ws/devel/lib/imu_3dm_gx4/imu_3dm_gx4
[ 63%] Built target imu_3dm_gx4
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

Problem with starting the simulator, PATH is not set.

When I try to run the simulator I have the following error: environment variable 'AR_CONFIG_PATH' is not set. I followed the tutorial and ran setupEnvLocal.sh file (it returned me these two errors:
./setupEnvLocal.sh: 9: ./setupEnvLocal.sh: Bad substitution
./setupEnvLocal.sh: 10: ./setupEnvLocal.sh: source: not found)

When I changed the first line from #!/bin/sh to #!/bin/bash I dont have these errors anymore, but still the simulator does not work. Can you help me?

Thank you in Advance
Adrian

Running with Kinetic on Ubuntu 16.04

Open issues in 16.04 with kinetic:
packages that must install from source:

  • camera1394
  • driver_common
  • hector_gazebo (a gazebo 7 compatible branch)
  • ros_control (not completely sure if this is required, but can't get simulation to start with ros-kinetic-controller-manager through cmd line)

before full compilation, compile driver_base with: catkin_make --pkg driver_base

our own nodes that don't compile right now:

  • stateEstimator

Joint controllers for simulation don't seem to work, needs more debugging

Compiling error with GPU

I use the kinetic-devel branch. When I compile it in Ubuntu 16.04, there are some compiling errors with respect to CUDA in the autorally_control package.

I got the following error:

/home/gaowei/catkin_ws/src/autorally/autorally_control/include/autorally_control/path_integral/generalized_linear.cut(98): error: a pointer to a bound function may only be used to call the function
/home/gaowei/catkin_ws/src/autorally/autorally_control/include/autorally_control/path_integral/neural_net_model.cut(79): error: a pointer to a bound function may only be used to call the function
/home/gaowei/catkin_ws/src/autorally/autorally_control/include/autorally_control/path_integral/neural_net_model.cut(80): error: a pointer to a bound function may only be used to call the function
/home/gaowei/catkin_ws/src/autorally/autorally_control/include/autorally_control/path_integral/generalized_linear.cut(98): error: a pointer to a bound function may only be used to call the function

Does anyone have any hint on this?
Thanks a lot!

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.