set_autopilot now uses the TM port instead of the TM object
This commit is contained in:
parent
50281d7ecb
commit
5d177eb4bb
|
@ -35,14 +35,12 @@ namespace client {
|
|||
: Actor(std::move(init)),
|
||||
_is_control_sticky(GetControlIsSticky(GetAttributes())) {}
|
||||
|
||||
void Vehicle::SetAutopilot(bool enabled, SharedPtr<TM> tm) {
|
||||
if(tm == nullptr ) {
|
||||
tm = MakeShared<TM>(GetEpisode());
|
||||
}
|
||||
void Vehicle::SetAutopilot(bool enabled, uint16_t tm_port) {
|
||||
TM tm(GetEpisode(), tm_port);
|
||||
if (enabled) {
|
||||
tm->RegisterVehicles({shared_from_this()});
|
||||
tm.RegisterVehicles({shared_from_this()});
|
||||
} else {
|
||||
tm->UnregisterVehicles({shared_from_this()});
|
||||
tm.UnregisterVehicles({shared_from_this()});
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@ namespace client {
|
|||
using ActorState::GetBoundingBox;
|
||||
|
||||
/// Switch on/off this vehicle's autopilot.
|
||||
void SetAutopilot(bool enabled = true, SharedPtr<TM> tm = nullptr);
|
||||
void SetAutopilot(bool enabled = true, uint16_t tm_port = TM_DEFAULT_PORT);
|
||||
|
||||
/// Apply @a control to this vehicle.
|
||||
void ApplyControl(const Control &control);
|
||||
|
|
|
@ -148,13 +148,13 @@ namespace rpc {
|
|||
SetAutopilot(
|
||||
ActorId id,
|
||||
bool value,
|
||||
SharedPtr<ctm::TrafficManager> tm = nullptr)
|
||||
uint16_t tm_port)
|
||||
: actor(id),
|
||||
enabled(value),
|
||||
tm(tm) {}
|
||||
tm_port(tm_port) {}
|
||||
ActorId actor;
|
||||
bool enabled;
|
||||
SharedPtr<ctm::TrafficManager> tm;
|
||||
uint16_t tm_port;
|
||||
MSGPACK_DEFINE_ARRAY(actor, enabled);
|
||||
};
|
||||
|
||||
|
|
|
@ -116,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", CALL_WITHOUT_GIL_2(cc::Vehicle, SetAutopilot, bool, carla::SharedPtr<ctm::TrafficManager>), (arg("enabled") = true, arg("tm") = boost::python::object() ))
|
||||
.def("set_autopilot", CALL_WITHOUT_GIL_2(cc::Vehicle, SetAutopilot, bool, uint16_t), (arg("enabled") = true, arg("tm_port") = TM_DEFAULT_PORT))
|
||||
.def("get_speed_limit", &cc::Vehicle::GetSpeedLimit)
|
||||
.def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState)
|
||||
.def("is_at_traffic_light", &cc::Vehicle::IsAtTrafficLight)
|
||||
|
|
|
@ -60,7 +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::shared_ptr<carla::traffic_manager::TrafficManager> tm = nullptr;
|
||||
uint16_t tm_port = 8000;
|
||||
|
||||
std::atomic<size_t> vehicles_to_enable_index;
|
||||
std::atomic<size_t> vehicles_to_disable_index;
|
||||
|
@ -84,7 +84,7 @@ static auto ApplyBatchCommandsSync(
|
|||
auto &spawn = boost::get<carla::rpc::Command::SpawnActor>(cmd_type);
|
||||
for (auto &cmd : spawn.do_after) {
|
||||
if (cmd.command.type() == typeid(carla::rpc::Command::SetAutopilot)) {
|
||||
tm = boost::get<carla::rpc::Command::SetAutopilot>(cmd.command).tm;
|
||||
tm_port = boost::get<carla::rpc::Command::SetAutopilot>(cmd.command).tm_port;
|
||||
autopilotValue = boost::get<carla::rpc::Command::SetAutopilot>(cmd.command).enabled;
|
||||
isAutopilot = true;
|
||||
}
|
||||
|
@ -92,7 +92,7 @@ static auto ApplyBatchCommandsSync(
|
|||
}
|
||||
// check SetAutopilot command
|
||||
else if (cmd_type_info == typeid(carla::rpc::Command::SetAutopilot)) {
|
||||
tm = boost::get<carla::rpc::Command::SetAutopilot>(cmd_type).tm;
|
||||
tm_port = boost::get<carla::rpc::Command::SetAutopilot>(cmd_type).tm_port;
|
||||
autopilotValue = boost::get<carla::rpc::Command::SetAutopilot>(cmd_type).enabled;
|
||||
isAutopilot = true;
|
||||
}
|
||||
|
@ -148,13 +148,8 @@ static auto ApplyBatchCommandsSync(
|
|||
|
||||
// check if any autopilot command was sent
|
||||
if (vehicles_to_enable.size() || vehicles_to_disable.size()) {
|
||||
if(tm){
|
||||
tm->RegisterVehicles(vehicles_to_enable);
|
||||
tm->UnregisterVehicles(vehicles_to_disable);
|
||||
} else {
|
||||
self.GetInstanceTM().RegisterVehicles(vehicles_to_enable);
|
||||
self.GetInstanceTM().UnregisterVehicles(vehicles_to_disable);
|
||||
}
|
||||
self.GetInstanceTM(tm_port).RegisterVehicles(vehicles_to_enable);
|
||||
self.GetInstanceTM(tm_port).UnregisterVehicles(vehicles_to_disable);
|
||||
}
|
||||
|
||||
return result;
|
||||
|
|
|
@ -8,6 +8,8 @@
|
|||
#include <carla/rpc/Command.h>
|
||||
#include <carla/rpc/CommandResponse.h>
|
||||
|
||||
#define TM_DEFAULT_PORT 8000
|
||||
|
||||
namespace command_impl {
|
||||
|
||||
template <typename T>
|
||||
|
@ -47,10 +49,8 @@ void export_commands() {
|
|||
namespace cc = carla::client;
|
||||
namespace cg = carla::geom;
|
||||
namespace cr = carla::rpc;
|
||||
namespace ctm = carla::traffic_manager;
|
||||
|
||||
using ActorPtr = carla::SharedPtr<cc::Actor>;
|
||||
using TMPtr = carla::SharedPtr<ctm::TrafficManager>;
|
||||
|
||||
object command_module(handle<>(borrowed(PyImport_AddModule("libcarla.command"))));
|
||||
scope().attr("command") = command_module;
|
||||
|
@ -152,10 +152,10 @@ void export_commands() {
|
|||
;
|
||||
|
||||
class_<cr::Command::SetAutopilot>("SetAutopilot")
|
||||
.def("__init__", &command_impl::CustomInit<ActorPtr, bool, TMPtr>, (arg("actor"), arg("enabled"), arg("tm") = boost::python::object() ))
|
||||
.def(init<cr::ActorId, bool, TMPtr>((arg("actor_id"), arg("enabled"), arg("tm") = boost::python::object() )))
|
||||
.def("__init__", &command_impl::CustomInit<ActorPtr, bool, uint16_t>, (arg("actor"), arg("enabled"), arg("tm_port") = TM_DEFAULT_PORT ))
|
||||
.def(init<cr::ActorId, bool, uint16_t>((arg("actor_id"), arg("enabled"), arg("tm_port") = TM_DEFAULT_PORT )))
|
||||
.def_readwrite("actor_id", &cr::Command::SetAutopilot::actor)
|
||||
.def_readwrite("tm", &cr::Command::SetAutopilot::tm)
|
||||
.def_readwrite("tm_port", &cr::Command::SetAutopilot::tm_port)
|
||||
.def_readwrite("enabled", &cr::Command::SetAutopilot::enabled)
|
||||
;
|
||||
|
||||
|
|
|
@ -17,6 +17,7 @@ void export_trafficmanager() {
|
|||
using namespace boost::python;
|
||||
|
||||
class_<carla::traffic_manager::TrafficManager>("TrafficManager", no_init)
|
||||
.def("get_port", &carla::traffic_manager::TrafficManager::Port)
|
||||
.def("vehicle_percentage_speed_difference", &carla::traffic_manager::TrafficManager::SetPercentageSpeedDifference)
|
||||
.def("global_percentage_speed_difference", &carla::traffic_manager::TrafficManager::SetGlobalPercentageSpeedDifference)
|
||||
.def("collision_detection", &carla::traffic_manager::TrafficManager::SetCollisionDetection)
|
||||
|
|
|
@ -152,7 +152,7 @@ def main():
|
|||
driver_id = random.choice(blueprint.get_attribute('driver_id').recommended_values)
|
||||
blueprint.set_attribute('driver_id', driver_id)
|
||||
blueprint.set_attribute('role_name', 'autopilot')
|
||||
batch.append(SpawnActor(blueprint, transform).then(SetAutopilot(FutureActor, True)))
|
||||
batch.append(SpawnActor(blueprint, transform).then(SetAutopilot(FutureActor, True, traffic_manager.get_port())))
|
||||
|
||||
for response in client.apply_batch_sync(batch, synchronous_master):
|
||||
if response.error:
|
||||
|
|
Loading…
Reference in New Issue