Updated set_autopilot to get tm as a parameter

This commit is contained in:
doterop 2020-03-31 17:21:06 +02:00 committed by Jacopo Bartiromo
parent 6b1a5db4f6
commit f2f4b229d7
7 changed files with 46 additions and 17 deletions

View File

@ -15,9 +15,11 @@
#include "carla/trafficmanager/TrafficManager.h"
namespace carla {
using TM = traffic_manager::TrafficManager;
namespace client {
using TM = traffic_manager::TrafficManager;
template <typename AttributesT>
static bool GetControlIsSticky(const AttributesT &attributes) {
@ -33,8 +35,7 @@ namespace client {
: Actor(std::move(init)),
_is_control_sticky(GetControlIsSticky(GetAttributes())) {}
void Vehicle::SetAutopilot(bool enabled) {
TM tm(GetEpisode());
void Vehicle::SetAutopilot(TM& tm, bool enabled) {
if (enabled) {
tm.RegisterVehicles({shared_from_this()});
} else {

View File

@ -13,6 +13,11 @@
#include "carla/rpc/VehiclePhysicsControl.h"
namespace carla {
namespace traffic_manager {
class TrafficManager;
}
namespace client {
class TrafficLight;
@ -23,13 +28,14 @@ namespace client {
using Control = rpc::VehicleControl;
using PhysicsControl = rpc::VehiclePhysicsControl;
using LightState = rpc::VehicleLightState::LightState;
using TM = traffic_manager::TrafficManager;
explicit Vehicle(ActorInitializer init);
using ActorState::GetBoundingBox;
/// Switch on/off this vehicle's autopilot.
void SetAutopilot(bool enabled = true);
void SetAutopilot(TM& tm, bool enabled = true);
/// Apply @a control to this vehicle.
void ApplyControl(const Control &control);

View File

@ -17,6 +17,11 @@
#include <boost/variant.hpp>
namespace carla {
namespace traffic_manager {
class TrafficManager;
}
namespace rpc {
class Command {
@ -135,11 +140,15 @@ namespace rpc {
};
struct SetAutopilot : CommandBase<SetAutopilot> {
using TM = traffic_manager::TrafficManager;
SetAutopilot() = default;
SetAutopilot(ActorId id, bool value)
SetAutopilot(ActorId id, /* TM tm, */ bool value)
: actor(id),
// tm(tm),
enabled(value) {}
ActorId actor;
// boost::optional<TM> tm;
bool enabled;
MSGPACK_DEFINE_ARRAY(actor, enabled);
};

View File

@ -10,6 +10,7 @@
#include <carla/client/Walker.h>
#include <carla/client/WalkerAIController.h>
#include <carla/rpc/TrafficLightState.h>
#include <carla/trafficmanager/TrafficManager.h>
#include <boost/python/suite/indexing/vector_indexing_suite.hpp>
@ -53,6 +54,7 @@ void export_actor() {
using namespace boost::python;
namespace cc = carla::client;
namespace cr = carla::rpc;
namespace ctm = carla::traffic_manager;
class_<std::vector<int>>("vector_of_ints")
.def(vector_indexing_suite<std::vector<int>>())
@ -114,7 +116,7 @@ void export_actor() {
.def("get_light_state", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetLightState))
.def("apply_physics_control", &cc::Vehicle::ApplyPhysicsControl, (arg("physics_control")))
.def("get_physics_control", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetPhysicsControl))
.def("set_autopilot", &cc::Vehicle::SetAutopilot, (arg("enabled") = true))
.def("set_autopilot", &cc::Vehicle::SetAutopilot, (arg("TM"), arg("enabled") = true))
.def("get_speed_limit", &cc::Vehicle::GetSpeedLimit)
.def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState)
.def("is_at_traffic_light", &cc::Vehicle::IsAtTrafficLight)

View File

@ -41,6 +41,9 @@ static auto ApplyBatchCommandsSync(
const carla::client::Client &self,
const boost::python::object &commands,
bool do_tick) {
carla::log_warning("ApplyBatchCommandsSync");
using CommandType = carla::rpc::Command;
std::vector<CommandType> cmds {
boost::python::stl_input_iterator<CommandType>(commands),
@ -57,6 +60,7 @@ static auto ApplyBatchCommandsSync(
std::vector<carla::traffic_manager::ActorPtr> vehicles_to_enable(cmds.size(), nullptr);
std::vector<carla::traffic_manager::ActorPtr> vehicles_to_disable(cmds.size(), nullptr);
carla::client::World world = self.GetWorld();
boost::optional<carla::traffic_manager::TrafficManager> tm;
std::atomic<size_t> vehicles_to_enable_index;
std::atomic<size_t> vehicles_to_disable_index;
@ -65,6 +69,7 @@ static auto ApplyBatchCommandsSync(
vehicles_to_disable_index.store(0);
auto ProcessCommand = [&](size_t min_index, size_t max_index) {
carla::log_warning("ApplyBatchCommandsSync ProcessCommand");
for (size_t i = min_index; i < max_index; ++i) {
if (!responses[i].HasError()) {
@ -88,6 +93,7 @@ static auto ApplyBatchCommandsSync(
// check SetAutopilot command
else if (cmd_type_info == typeid(carla::rpc::Command::SetAutopilot)) {
autopilotValue = boost::get<carla::rpc::Command::SetAutopilot>(cmd_type).enabled;
// tm = boost::get<carla::rpc::Command::SetAutopilot>(cmd_type).tm;
isAutopilot = true;
}
@ -141,9 +147,9 @@ static auto ApplyBatchCommandsSync(
vehicles_to_disable.shrink_to_fit();
// check if any autopilot command was sent
if ((vehicles_to_enable.size() || vehicles_to_disable.size())) {
self.GetInstanceTM().RegisterVehicles(vehicles_to_enable);
self.GetInstanceTM().UnregisterVehicles(vehicles_to_disable);
if (tm && (vehicles_to_enable.size() || vehicles_to_disable.size())) {
tm->RegisterVehicles(vehicles_to_enable);
tm->UnregisterVehicles(vehicles_to_disable);
}
return result;

View File

@ -47,6 +47,7 @@ void export_commands() {
namespace cc = carla::client;
namespace cg = carla::geom;
namespace cr = carla::rpc;
namespace ctm = carla::traffic_manager;
using ActorPtr = boost::shared_ptr<cc::Actor>;
@ -151,8 +152,9 @@ void export_commands() {
class_<cr::Command::SetAutopilot>("SetAutopilot")
.def("__init__", &command_impl::CustomInit<ActorPtr, bool>, (arg("actor"), arg("enabled")))
.def(init<cr::ActorId, bool>((arg("actor_id"), arg("enabled"))))
.def(init<cr::ActorId, /* ctm::TrafficManager, */ bool>((arg("actor_id"), /* arg("tm"), */ arg("enabled"))))
.def_readwrite("actor_id", &cr::Command::SetAutopilot::actor)
//.def_readwrite("tm", &cr::Command::SetAutopilot::tm)
.def_readwrite("enabled", &cr::Command::SetAutopilot::enabled)
;

View File

@ -155,7 +155,7 @@ def get_actor_display_name(actor, truncate=250):
class World(object):
def __init__(self, carla_world, hud, args):
def __init__(self, carla_world, tm, hud, args):
self.world = carla_world
self.actor_role_name = args.rolename
try:
@ -165,6 +165,7 @@ class World(object):
print(' The server could not send the OpenDRIVE (.xodr) file:')
print(' Make sure it exists, has the same name of your town, and is correct.')
sys.exit(1)
self.tm = tm
self.hud = hud
self.player = None
self.collision_sensor = None
@ -285,7 +286,7 @@ class KeyboardControl(object):
if isinstance(world.player, carla.Vehicle):
self._control = carla.VehicleControl()
self._lights = carla.VehicleLightState.NONE
world.player.set_autopilot(self._autopilot_enabled)
world.player.set_autopilot(world.tm, self._autopilot_enabled)
world.player.set_light_state(self._lights)
elif isinstance(world.player, carla.Walker):
self._control = carla.WalkerControl()
@ -307,9 +308,9 @@ class KeyboardControl(object):
return True
elif event.key == K_BACKSPACE:
if self._autopilot_enabled:
world.player.set_autopilot(False)
world.player.set_autopilot(world.tm, False)
world.restart()
world.player.set_autopilot(True)
world.player.set_autopilot(world.tm, True)
else:
world.restart()
elif event.key == K_F1:
@ -350,7 +351,7 @@ class KeyboardControl(object):
world.destroy_sensors()
# disable autopilot
self._autopilot_enabled = False
world.player.set_autopilot(self._autopilot_enabled)
world.player.set_autopilot(world.tm, self._autopilot_enabled)
world.hud.notification("Replaying file 'manual_recording.rec'")
# replayer
client.replay_file("manual_recording.rec", world.recording_start, 0, 0)
@ -381,7 +382,7 @@ class KeyboardControl(object):
self._control.gear = self._control.gear + 1
elif event.key == K_p and not pygame.key.get_mods() & KMOD_CTRL:
self._autopilot_enabled = not self._autopilot_enabled
world.player.set_autopilot(self._autopilot_enabled)
world.player.set_autopilot(world.tm, self._autopilot_enabled)
world.hud.notification(
'Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
elif event.key == K_l and pygame.key.get_mods() & KMOD_CTRL:
@ -1011,8 +1012,10 @@ def game_loop(args):
(args.width, args.height),
pygame.HWSURFACE | pygame.DOUBLEBUF)
# TODO: args.tm_port
tm = client.get_trafficmanager(8000)
hud = HUD(args.width, args.height)
world = World(client.get_world(), hud, args)
world = World(client.get_world(), tm, hud, args)
controller = KeyboardControl(world, args.autopilot)
clock = pygame.time.Clock()