Merge branch 'master' into com
|
@ -1,7 +1,7 @@
|
|||
Build
|
||||
Dist
|
||||
Doxygen
|
||||
PythonClient/dist
|
||||
Deprecated/PythonClient/dist
|
||||
Util/Build
|
||||
Install
|
||||
|
||||
|
|
|
@ -45,10 +45,10 @@ matrix:
|
|||
- python
|
||||
- python-pip
|
||||
install:
|
||||
- pip2 install -q --user -r PythonClient/requirements.txt
|
||||
- pip2 install -q --user -r Deprecated/PythonClient/requirements.txt
|
||||
- pip2 install -q --user pylint
|
||||
script:
|
||||
- pylint --disable=R,C --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py
|
||||
- pylint --disable=R,C --rcfile=Deprecated/PythonClient/.pylintrc Deprecated/PythonClient/carla Deprecated/PythonClient/*.py
|
||||
|
||||
- env: TEST="MkDocs"
|
||||
install:
|
||||
|
|
Before Width: | Height: | Size: 534 KiB After Width: | Height: | Size: 534 KiB |
Before Width: | Height: | Size: 27 KiB After Width: | Height: | Size: 27 KiB |
Before Width: | Height: | Size: 33 KiB After Width: | Height: | Size: 33 KiB |
Before Width: | Height: | Size: 175 KiB After Width: | Height: | Size: 175 KiB |
Before Width: | Height: | Size: 400 KiB After Width: | Height: | Size: 400 KiB |
Before Width: | Height: | Size: 10 KiB After Width: | Height: | Size: 10 KiB |
Before Width: | Height: | Size: 15 KiB After Width: | Height: | Size: 15 KiB |
|
@ -274,7 +274,7 @@ class PointCloud(SensorData):
|
|||
|
||||
# Open the file and save with the specific PLY format.
|
||||
with open(filename, 'w+') as ply_file:
|
||||
ply_file.write('\n'.join([construct_ply_header(), ply]))
|
||||
ply_file.write('\n'.join([construct_ply_header(), ply, '']))
|
||||
|
||||
def __len__(self):
|
||||
return len(self.array)
|
|
@ -131,7 +131,4 @@ If you see a red mark, please correct your code accordingly.
|
|||
- [ ] Your branch is up-to-date with the `master` branch and tested with latest changes
|
||||
- [ ] Extended the README / documentation, if necessary
|
||||
- [ ] Code compiles correctly
|
||||
- [ ] All tests passing
|
||||
- [ ] `make check`
|
||||
- [ ] `pylint --disable=R,C --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py`
|
||||
- [ ] `cppcheck . -iBuild -i.pb.cc --enable=warning`
|
||||
- [ ] All tests passing with `make check`
|
||||
|
|
|
@ -213,7 +213,7 @@ vector as we show in the following code excerpt:
|
|||
|
||||
|
||||
|
||||
The full code could be found at [basic_experiment_suite.py](https://github.com/carla-simulator/carla/blob/master/PythonClient/carla/driving_benchmark/experiment_suites/basic_experiment_suite.py)
|
||||
The full code could be found at [basic_experiment_suite.py](https://github.com/carla-simulator/carla/blob/master/Deprecated/PythonClient/carla/driving_benchmark/experiment_suites/basic_experiment_suite.py)
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -1,10 +1,11 @@
|
|||
<h1>Cameras and sensors</h1>
|
||||
|
||||
!!! important
|
||||
This document still refers to the 0.8.X API (stable version). The
|
||||
proceedings stated here may not apply to latest versions, 0.9.0 or later.
|
||||
Latest versions introduced significant changes in the API, we are still
|
||||
working on documenting everything, sorry for the inconvenience.
|
||||
This document still refers to the 0.8.X API (stable version), this API is
|
||||
currently located under _"Deprecated/PythonClient"_. The proceedings stated
|
||||
here may not apply to latest versions, 0.9.0 or later. Latest versions
|
||||
introduced significant changes in the API, we are still working on
|
||||
documenting everything, sorry for the inconvenience.
|
||||
|
||||
!!! important
|
||||
Since version 0.8.0 the positions of the sensors are specified in meters
|
||||
|
@ -30,7 +31,8 @@ moment there are four different sensors available.
|
|||
The images are sent by the server as a BGRA array of bytes. The provided
|
||||
Python client retrieves the images in this format, it's up to the users to
|
||||
parse the images and convert them to the desired format. There are some
|
||||
examples in the PythonClient folder showing how to parse the images.
|
||||
examples in the Deprecated/PythonClient folder showing how to parse the
|
||||
images.
|
||||
|
||||
There is a fourth post-processing effect available for cameras, _None_, which
|
||||
provides a view with of the scene with no effect, not even scene lighting; we
|
||||
|
@ -46,7 +48,7 @@ number_ matches the one received in the measurements. This is especially useful
|
|||
for running the simulator in asynchronous mode and synchronize sensor data on
|
||||
the client side.
|
||||
|
||||
[clientexamplelink]: https://github.com/carla-simulator/carla/blob/master/PythonClient/client_example.py
|
||||
[clientexamplelink]: https://github.com/carla-simulator/carla/blob/master/Deprecated/PythonClient/client_example.py
|
||||
[settingslink]: https://github.com/carla-simulator/carla/blob/master/Docs/Example.CarlaSettings.ini
|
||||
[imgconvlink]: https://github.com/carla-simulator/carla/tree/master/Util/ImageConverter
|
||||
|
||||
|
@ -128,7 +130,7 @@ Our max render distance (far) is 1km.
|
|||
|
||||
The generated "depth map" images are usually converted to a logarithmic
|
||||
grayscale for display. A point cloud can also be extracted from depth images as
|
||||
seen in "PythonClient/point_cloud_example.py".
|
||||
seen in "Deprecated/PythonClient/point_cloud_example.py".
|
||||
|
||||
<h6>Python</h6>
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@ CARLA Design
|
|||
CARLA is composed by the following modules
|
||||
|
||||
* Client side
|
||||
- Python client API: "PythonClient/carla"
|
||||
- Python client API: "Deprecated/PythonClient/carla"
|
||||
* Server side
|
||||
- CarlaUE4 Unreal Engine project: "Unreal/CarlaUE4"
|
||||
- Carla plugin for Unreal Engine: "Unreal/CarlaUE4/Plugins/Carla"
|
||||
|
@ -20,7 +20,7 @@ Python client API
|
|||
-----------------
|
||||
|
||||
The client API provides a Python module for communicating with the CARLA server.
|
||||
In the folder "PythonClient", we provide several examples for scripting a CARLA
|
||||
In the folder "Deprecated/PythonClient", we provide several examples for scripting a CARLA
|
||||
client using the "carla" module.
|
||||
|
||||
CarlaUE4 Unreal Engine project
|
||||
|
|
|
@ -8,11 +8,11 @@ aspects of simulation, from environment to duration of each episode, it can
|
|||
retrieve data from different sensors, and send control instructions to the
|
||||
player vehicle.
|
||||
|
||||
PythonClient contents
|
||||
---------------------
|
||||
Deprecated/PythonClient contents
|
||||
--------------------------------
|
||||
|
||||
In the release package, inside the _"PythonClient"_ folder, we provide the
|
||||
Python API module together with some use examples.
|
||||
In the release package, inside the _"Deprecated/PythonClient"_ folder, we
|
||||
provide the Python API module together with some use examples.
|
||||
|
||||
File or folder | Description
|
||||
------------------------ | ------------
|
||||
|
@ -25,9 +25,9 @@ view_start_positions.py | Show all the possible start positions in a map
|
|||
|
||||
!!! note
|
||||
If you are building CARLA from source, the Python code is inside the
|
||||
_"PythonClient"_ folder in the CARLA repository. Bear in mind that the
|
||||
`master` branch contains latest fixes and changes that might be incompatible
|
||||
with the release version. Consider using the `stable` branch.
|
||||
_"Deprecated/PythonClient"_ folder in the CARLA repository. Bear in mind
|
||||
that the `master` branch contains latest fixes and changes that might be
|
||||
incompatible with the release version. Consider using the `stable` branch.
|
||||
|
||||
Install dependencies
|
||||
--------------------
|
||||
|
@ -37,7 +37,7 @@ given examples is also compatible with Python 2.7.
|
|||
|
||||
Install the dependencies with "pip" using the requirements file provided
|
||||
|
||||
$ pip install -r PythonClient/requirements.txt
|
||||
$ pip install -r Deprecated/PythonClient/requirements.txt
|
||||
|
||||
Running the client example
|
||||
--------------------------
|
||||
|
@ -96,7 +96,6 @@ You can see all the available options in the script's help
|
|||
|
||||
<h4>Running other examples</h4>
|
||||
|
||||
The other scripts present in the _"PythonClient"_ folder run in a similar
|
||||
fashion. We recommend now launching _"manual_control.py"_ for a GUI interface
|
||||
implemented with PyGame.
|
||||
|
||||
The other scripts present in the _"Deprecated/PythonClient"_ folder run in a
|
||||
similar fashion. We recommend now launching _"manual_control.py"_ for a GUI
|
||||
interface implemented with PyGame.
|
||||
|
|
|
@ -8,10 +8,7 @@ Checklist:
|
|||
- [ ] Your branch is up-to-date with the `master` branch and tested with latest changes
|
||||
- [ ] Extended the README / documentation, if necessary
|
||||
- [ ] Code compiles correctly
|
||||
- [ ] All tests passing
|
||||
- [ ] `make check`
|
||||
- [ ] `pylint --disable=R,C --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py`
|
||||
- [ ] `cppcheck . -iBuild -i.pb.cc --enable=warning`
|
||||
- [ ] All tests passing with `make check`
|
||||
|
||||
-->
|
||||
|
||||
|
|
|
@ -37,6 +37,19 @@ namespace client {
|
|||
});
|
||||
}
|
||||
|
||||
const ActorAttribute &ActorBlueprint::GetAttribute(const std::string &id) const {
|
||||
auto it = _attributes.find(id);
|
||||
if (it == _attributes.end()) {
|
||||
using namespace std::string_literals;
|
||||
throw std::out_of_range("attribute '"s + id + "' not found");
|
||||
}
|
||||
return it->second;
|
||||
}
|
||||
|
||||
void ActorBlueprint::SetAttribute(const std::string &id, std::string value) {
|
||||
const_cast<ActorAttribute &>(GetAttribute(id)).Set(std::move(value));
|
||||
}
|
||||
|
||||
rpc::ActorDescription ActorBlueprint::MakeActorDescription() const {
|
||||
rpc::ActorDescription description;
|
||||
description.uid = _uid;
|
||||
|
|
|
@ -76,18 +76,14 @@ namespace client {
|
|||
}
|
||||
|
||||
/// @throw std::out_of_range if no such element exists.
|
||||
const ActorAttribute &GetAttribute(const std::string &id) const {
|
||||
return _attributes.at(id);
|
||||
}
|
||||
const ActorAttribute &GetAttribute(const std::string &id) const;
|
||||
|
||||
/// Set the value of the attribute given by @a id.
|
||||
///
|
||||
/// @throw std::out_of_range if no such element exists.
|
||||
/// @throw InvalidAttributeValue if attribute is not modifiable.
|
||||
/// @throw InvalidAttributeValue if format does not match the attribute type.
|
||||
void SetAttribute(const std::string &id, std::string value) {
|
||||
_attributes.at(id).Set(std::move(value));
|
||||
}
|
||||
void SetAttribute(const std::string &id, std::string value);
|
||||
|
||||
size_t size() const {
|
||||
return _attributes.size();
|
||||
|
|
|
@ -31,6 +31,20 @@ namespace client {
|
|||
return SharedPtr<BlueprintLibrary>{new BlueprintLibrary(result)};
|
||||
}
|
||||
|
||||
BlueprintLibrary::const_pointer BlueprintLibrary::Find(const std::string &key) const {
|
||||
auto it = _blueprints.find(key);
|
||||
return it != _blueprints.end() ? &it->second : nullptr;
|
||||
}
|
||||
|
||||
BlueprintLibrary::const_reference BlueprintLibrary::at(const std::string &key) const {
|
||||
auto it = _blueprints.find(key);
|
||||
if (it == _blueprints.end()) {
|
||||
using namespace std::string_literals;
|
||||
throw std::out_of_range("blueprint '"s + key + "' not found");
|
||||
}
|
||||
return it->second;
|
||||
}
|
||||
|
||||
BlueprintLibrary::const_reference BlueprintLibrary::at(size_type pos) const {
|
||||
if (pos >= size())
|
||||
throw std::out_of_range("index out of range");
|
||||
|
|
|
@ -44,14 +44,10 @@ namespace client {
|
|||
/// @a wildcard_pattern.
|
||||
SharedPtr<BlueprintLibrary> Filter(const std::string &wildcard_pattern) const;
|
||||
|
||||
const_pointer Find(const std::string &key) const {
|
||||
auto it = _blueprints.find(key);
|
||||
return it != _blueprints.end() ? &it->second : nullptr;
|
||||
}
|
||||
const_pointer Find(const std::string &key) const;
|
||||
|
||||
const_reference at(const std::string &key) const {
|
||||
return _blueprints.at(key);
|
||||
}
|
||||
/// @throw std::out_of_range if no such element exists.
|
||||
const_reference at(const std::string &key) const;
|
||||
|
||||
/// @warning Linear complexity.
|
||||
const_reference operator[](size_type pos) const {
|
||||
|
@ -59,6 +55,7 @@ namespace client {
|
|||
}
|
||||
|
||||
/// @warning Linear complexity.
|
||||
/// @throw std::out_of_range if !(pos < size()).
|
||||
const_reference at(size_type pos) const;
|
||||
|
||||
const_iterator begin() const /*noexcept*/ {
|
||||
|
|
|
@ -11,6 +11,8 @@
|
|||
|
||||
#include <exception>
|
||||
|
||||
#include <exception>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
|
||||
MSGPACK_ADD_ENUM(carla::rpc::ActorAttributeType);
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
# include "Carla/Actor/ActorAttribute.h"
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
namespace carla {
|
||||
namespace rpc {
|
||||
|
||||
|
|
|
@ -13,6 +13,10 @@
|
|||
|
||||
#include <vector>
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
# include "Carla/Actor/ActorDescription.h"
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
namespace carla {
|
||||
namespace rpc {
|
||||
|
||||
|
|
|
@ -21,6 +21,6 @@
|
|||
#include <cstdint>
|
||||
#include <iostream>
|
||||
|
||||
constexpr uint16_t TESTING_PORT = 2000u;
|
||||
constexpr uint16_t TESTING_PORT = 2017u;
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
|
|
@ -20,7 +20,7 @@ def get_libcarla_extensions():
|
|||
sources = ['source/libcarla/libcarla.cpp']
|
||||
|
||||
if os.name == "posix":
|
||||
if platform.dist()[0] == "Ubuntu":
|
||||
if platform.dist()[0].lower() in ["ubuntu", "debian"]:
|
||||
pwd = os.path.dirname(os.path.realpath(__file__))
|
||||
pylib = "libboost_python%d%d.a" % (sys.version_info.major,
|
||||
sys.version_info.minor)
|
||||
|
|
|
@ -44,6 +44,7 @@ If you use CARLA, please cite our CoRL’17 paper.
|
|||
_CARLA: An Open Urban Driving Simulator_<br>Alexey Dosovitskiy, German Ros,
|
||||
Felipe Codevilla, Antonio Lopez, Vladlen Koltun; PMLR 78:1-16
|
||||
[[PDF](http://proceedings.mlr.press/v78/dosovitskiy17a/dosovitskiy17a.pdf)]
|
||||
[[talk](https://www.youtube.com/watch?v=xfyK03MEZ9Q&feature=youtu.be&t=2h44m30s)]
|
||||
|
||||
|
||||
```
|
||||
|
|
|
@ -28,6 +28,7 @@ r.DefaultFeature.AmbientOcclusionStaticFraction=False
|
|||
r.DefaultFeature.AutoExposure=False
|
||||
r.CustomDepth=3
|
||||
r.Streaming.PoolSize=2000
|
||||
r.TextureStreaming=False
|
||||
|
||||
[/Script/AIModule.AISense_Sight]
|
||||
bAutoRegisterAllPawnsAsSources=False
|
||||
|
|
|
@ -128,6 +128,12 @@ public:
|
|||
State = InState;
|
||||
}
|
||||
|
||||
UFUNCTION(Category = "AI Controller", BlueprintCallable)
|
||||
ECarlaWheeledVehicleState GetAIVehicleState() const
|
||||
{
|
||||
return State;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
/// Current state of the vehicle controller (for debugging purposes).
|
||||
|
|
|
@ -13,18 +13,18 @@ struct CARLA_API FVehicleControl
|
|||
{
|
||||
GENERATED_BODY()
|
||||
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere)
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite)
|
||||
float Throttle = 0.0f;
|
||||
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere)
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite)
|
||||
float Steer = 0.0f;
|
||||
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere)
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite)
|
||||
float Brake = 0.0f;
|
||||
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere)
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite)
|
||||
bool bHandBrake = false;
|
||||
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere)
|
||||
UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite)
|
||||
bool bReverse = false;
|
||||
};
|
||||
|
|
|
@ -236,7 +236,7 @@ float AWheeledVehicleAIController::GoToNextTargetLocation(FVector &Direction)
|
|||
return FVector{Result.X, Result.Y, CurrentLocation.Z};
|
||||
}();
|
||||
|
||||
if (Target.Equals(CurrentLocation, 80.0f)) {
|
||||
if (Target.Equals(CurrentLocation, 200.0f)) {
|
||||
TargetLocations.pop();
|
||||
if (!TargetLocations.empty()) {
|
||||
return GoToNextTargetLocation(Direction);
|
||||
|
|
|
@ -185,8 +185,8 @@ public:
|
|||
/// @name AI
|
||||
// ===========================================================================
|
||||
/// @{
|
||||
protected:
|
||||
|
||||
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
|
||||
const FVehicleControl &GetAutopilotControl() const
|
||||
{
|
||||
return AutopilotControl;
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
set PROTOBUF_SRC_DIR=Proto
|
||||
set PROTOBUF_CPP_OUT_DIR=CarlaServer/source/carla/server
|
||||
set PROTOBUF_PY_OUT_DIR=../PythonClient/carla
|
||||
set PROTOBUF_PY_OUT_DIR=../Deprecated/PythonClient/carla
|
||||
set PROTO_BASENAME=carla_server
|
||||
|
||||
if "%1" == "--clean" (
|
||||
|
|
|
@ -7,7 +7,7 @@ pushd "$SCRIPT_DIR" >/dev/null
|
|||
|
||||
PROTOBUF_SRC_DIR=Proto
|
||||
PROTOBUF_CPP_OUT_DIR=CarlaServer/source/carla/server
|
||||
PROTOBUF_PY_OUT_DIR=../PythonClient/carla
|
||||
PROTOBUF_PY_OUT_DIR=../Deprecated/PythonClient/carla
|
||||
PROTO_BASENAME=carla_server
|
||||
|
||||
if [ "$1" == "--clean" ]; then
|
||||
|
|
|
@ -16,7 +16,7 @@ This ros package aims at providing a simple ros bridge for carla simulator.
|
|||
- [x] Lidar sensor support
|
||||
- [x] Transform publications
|
||||
- [x] Manual control using ackermann msg
|
||||
- [x] Autopilot mode using rosparam
|
||||
- [x] Autopilot mode using rosparam
|
||||
- [x] Rosbag in the bridge (in order to avoid rosbag recoard -a small time errors)
|
||||
- [x] Handle ros dependencies
|
||||
- [x] Marker/bounding box messages for cars/pedestrian
|
||||
|
@ -33,21 +33,21 @@ This ros package aims at providing a simple ros bridge for carla simulator.
|
|||
mkdir -p ~/ros/catkin_ws_for_carla/src
|
||||
cd ~/ros/catkin_ws_for_carla
|
||||
source /opt/ros/kinetic/setup.bash
|
||||
catkin_make
|
||||
catkin_make
|
||||
source ~/ros/catkin_ws_for_carla/devel/setup.bash
|
||||
|
||||
For more information about configuring a ros environment see
|
||||
|
||||
For more information about configuring a ros environment see
|
||||
http://wiki.ros.org/ROS/Tutorials/InstallingandConfiguringROSEnvironment
|
||||
|
||||
## Install carla python client in your workspace
|
||||
|
||||
cd carla/PythonClient
|
||||
pip2 install -e . --user --upgrade
|
||||
|
||||
cd carla/Deprecated/PythonClient
|
||||
pip2 install -e . --user --upgrade
|
||||
|
||||
Check the installation is successfull by trying to import carla from python:
|
||||
|
||||
python -c 'import carla;print("Success")'
|
||||
|
||||
|
||||
You should see the Success message without any errors.
|
||||
|
||||
### Install recent protobuf version [optional]
|
||||
|
@ -55,9 +55,9 @@ You should see the Success message without any errors.
|
|||
sudo apt-get remove python-protobuf
|
||||
sudo pip2 install --upgrade protobuf
|
||||
|
||||
|
||||
|
||||
### Add the carla_ros_bridge in the catkin workspace
|
||||
|
||||
|
||||
Run the following command after replacing [PATH_TO_CARLA] with the actual path to carla directory on your machine:
|
||||
|
||||
ln -s [PATH_TO_CARLA]/carla_ros_bridge/ ~/ros/catkin_ws_for_carla/src/
|
||||
|
@ -67,23 +67,23 @@ Run the following command after replacing [PATH_TO_CARLA] with the actual path t
|
|||
cd ~/ros/catkin_ws_for_carla
|
||||
catkin_make
|
||||
source ~/ros/catkin_ws_for_carla/devel/setup.bash
|
||||
|
||||
|
||||
|
||||
### Test your installation
|
||||
|
||||
|
||||
If you use the builded binary (0.8.2):
|
||||
|
||||
./CarlaUE4 -carla-server -windowed -ResX=320 -ResY=240
|
||||
./CarlaUE4.sh -carla-server -windowed -ResX=320 -ResY=240
|
||||
|
||||
|
||||
|
||||
Wait for the message:
|
||||
|
||||
Waiting for the client to connect...
|
||||
|
||||
|
||||
Then run the tests
|
||||
|
||||
|
||||
rostest carla_ros_bridge ros_bridge_client.test
|
||||
|
||||
|
||||
you should see:
|
||||
|
||||
[carla_ros_bridge.rosunit-testTopics/test_publish][passed]
|
||||
|
@ -92,7 +92,7 @@ you should see:
|
|||
* RESULT: SUCCESS
|
||||
|
||||
|
||||
|
||||
|
||||
# Start the ros bridge
|
||||
|
||||
First run the simulator (see carla documentation: http://carla.readthedocs.io/en/latest/)
|
||||
|
@ -108,11 +108,11 @@ Then start the ros bridge:
|
|||
|
||||
source ~/ros/catkin_ws_for_carla/devel/setup.bash
|
||||
roslaunch carla_ros_bridge client.launch
|
||||
|
||||
|
||||
To start the ros bridge with rviz use:
|
||||
|
||||
roslaunch carla_ros_bridge client_with_rviz.launch
|
||||
|
||||
|
||||
You can setup the wanted camera/sensors in config/settings.yaml.
|
||||
|
||||
# Autopilot control
|
||||
|
@ -120,13 +120,13 @@ You can setup the wanted camera/sensors in config/settings.yaml.
|
|||
To enable autopilot control set the ros param carla_autopilot to True
|
||||
|
||||
rosparam set carla_autopilot True
|
||||
|
||||
# Manual control
|
||||
|
||||
# Manual control
|
||||
|
||||
To enable manual control set the ros param carla_autopilot to False
|
||||
|
||||
rosparam set carla_autopilot False
|
||||
|
||||
|
||||
|
||||
Then you can send command to the car using the /ackermann_cmd topic.
|
||||
|
||||
|
@ -134,16 +134,16 @@ Example of forward movements, speed in in meters/sec.
|
|||
|
||||
rostopic pub /ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0,
|
||||
jerk: 0.0}" -r 10
|
||||
|
||||
|
||||
|
||||
|
||||
Example of forward with steering
|
||||
|
||||
|
||||
rostopic pub /ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 5.41, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0,
|
||||
jerk: 0.0}" -r 10
|
||||
|
||||
|
||||
Warning: the steering_angle is the driving angle (in radians) not the wheel angle, for now max wheel is set to 500 degrees.
|
||||
|
||||
|
||||
|
||||
|
||||
Example for backward :
|
||||
|
||||
rostopic pub /ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0, steering_angle_velocity: 0.0, speed: -10, acceleration: 0.0,
|
||||
|
|