diff --git a/python/delphyne/agents.cc b/python/delphyne/agents.cc index 8e3c178c4..7979ae480 100644 --- a/python/delphyne/agents.cc +++ b/python/delphyne/agents.cc @@ -7,6 +7,7 @@ ** Includes *****************************************************************************/ +#include #include #include @@ -53,7 +54,8 @@ PYBIND11_MODULE(agents, m) { py::arg("lane"), py::arg("direction_of_travel"), py::arg("longitudinal_position"), py::arg("lateral_offset"), py::arg("speed"), py::arg("nominal_speed"), - py::arg("road_geometry")); + py::arg("road_geometry")) + .def("set_speed", &delphyne::RailCar::SetSpeed); py::class_(m, "SimpleCar") .def(py::init(), diff --git a/python/delphyne/demos/crash.py b/python/delphyne/demos/crash.py index edf329079..c90f31924 100644 --- a/python/delphyne/demos/crash.py +++ b/python/delphyne/demos/crash.py @@ -56,12 +56,6 @@ def add_collision_callback(_, method): def _method_wrapper(self, callback): @wraps(callback) def _callback_wrapper(agents_in_collision): - simulator = self.get_simulator() - agents_in_collision = [ - (simulator.get_mutable_agent_by_id(agent1_id), - simulator.get_mutable_agent_by_id(agent2_id)) - for agent1_id, agent2_id in agents_in_collision - ] callback(self, agents_in_collision) return method(self, _callback_wrapper) return _method_wrapper diff --git a/python/delphyne/demos/scriptlets.py b/python/delphyne/demos/scriptlets.py index 805da9d62..33367f761 100644 --- a/python/delphyne/demos/scriptlets.py +++ b/python/delphyne/demos/scriptlets.py @@ -18,9 +18,12 @@ from __future__ import print_function +import os.path + import random import time +import delphyne.maliput as maliput import delphyne.simulation as simulation import delphyne.utilities as utilities @@ -89,6 +92,29 @@ def parse_arguments(): ) return parser.parse_args() + +class TimeMonitor(object): + ''' + A class to monitor the time on every callback and perform an action after + ten seconds have elapsed. + ''' + def __init__(self, simulator, agent): + self.simulator = simulator + self.agent = agent + self.changed_speed = False + + def check_tick(self): + ''' + The callback called on every simulator iteration. It checks + to see if the elapsed simulator_time is greater than 10 seconds, and + once it is, it changes the speed of the agent. + ''' + if self.simulator.get_current_simulation_time() >= 10.0 \ + and not self.changed_speed: + self.agent.set_speed(20.0) + self.changed_speed = True + + ############################################################################## # Main ############################################################################## @@ -101,19 +127,54 @@ def main(): stats = SimulationStats() simulator = simulation.AutomotiveSimulator() + + filename = "{0}/roads/circuit.yaml".format( + utilities.get_delphyne_resource_root()) + + if not os.path.isfile(filename): + print("Required file {} not found." + " Please, make sure to install the latest delphyne-gui." + .format(os.path.abspath(filename))) + quit() + + # The road geometry + road_geometry = simulator.set_road_geometry( + maliput.create_multilane_from_file( + file_path=filename + ) + ) + utilities.add_simple_car( simulator, name=str(0), position_x=0.0, position_y=0.0) + # Setup railcar + railcar_speed = 4.0 # (m/s) + railcar_s = 0.0 # (m) + robot_id = 1 + lane_1 = road_geometry.junction(2).segment(0).lane(0) + myagent = utilities.add_rail_car( + simulator, + name=str(robot_id), + lane=lane_1, + position=railcar_s, + offset=0.0, + speed=railcar_speed, + road_geometry=road_geometry) + runner = simulation.SimulatorRunner( simulator=simulator, time_step=0.001, # (secs) realtime_rate=args.realtime_rate, - paused=args.paused + paused=args.paused, + log=args.log, + logfile_name=args.logfile_name ) + monitor = TimeMonitor(simulator, myagent) + with utilities.launch_interactive_simulation(runner) as launcher: # Add a callback to record and print statistics runner.add_step_callback(stats.record_tick) @@ -121,6 +182,9 @@ def main(): # Add a second callback that prints a message roughly every 500 calls runner.add_step_callback(random_print) + # Add a third callback to check on the time elapsed and change speed + runner.add_step_callback(monitor.check_tick) + stats.start() if args.duration < 0: diff --git a/python/delphyne/maliput.cc b/python/delphyne/maliput.cc index bc7299654..eb9714e97 100644 --- a/python/delphyne/maliput.cc +++ b/python/delphyne/maliput.cc @@ -8,7 +8,6 @@ *****************************************************************************/ #include -#include #include #include diff --git a/python/delphyne/simulation.cc b/python/delphyne/simulation.cc index f47b5b108..ade2d3f31 100644 --- a/python/delphyne/simulation.cc +++ b/python/delphyne/simulation.cc @@ -123,18 +123,19 @@ PYBIND11_MODULE(simulation, m) { py::class_>(m, "AutomotiveSimulator") .def(py::init( [](void) { return std::make_unique>(); })) - .def("add_agent", &AutomotiveSimulator::AddAgent) - .def("get_agent_by_id", - &AutomotiveSimulator::GetAgentById, + .def("add_agent", &AutomotiveSimulator::AddAgent, py::return_value_policy::reference_internal) - .def("get_mutable_agent_by_id", - &AutomotiveSimulator::GetMutableAgentById, + .def("get_collisions", &AutomotiveSimulator::GetCollisions, py::return_value_policy::reference_internal) - .def("get_collisions", &AutomotiveSimulator::GetCollisions) .def("start", &AutomotiveSimulator::Start) .def("set_road_geometry", &AutomotiveSimulator::SetRoadGeometry, "Transfer a road geometry to the control of the simulator", - py::arg("road_geometry")); + py::arg("road_geometry")) + .def("get_current_simulation_time", + &AutomotiveSimulator::GetCurrentSimulationTime) + .def("get_mutable_context", + &AutomotiveSimulator::GetMutableContext, + py::return_value_policy::reference_internal); } /***************************************************************************** diff --git a/python/delphyne/utilities.py b/python/delphyne/utilities.py index efb668495..781297798 100644 --- a/python/delphyne/utilities.py +++ b/python/delphyne/utilities.py @@ -147,9 +147,9 @@ def add_rail_car(simulator, name, lane, position, offset, longitudinal_position=position, # lane s-coordinate (m) lateral_offset=offset, # lane r-coordinate (m) speed=speed, # initial speed in s-direction (m/s) - nominal_speed=5.0, # nominal_speed (m/s) + nominal_speed=20.0, # nominal_speed (m/s) road_geometry=road_geometry) # maliput road geometry - simulator.add_agent(agent) + return simulator.add_agent(agent) # pylint: disable=too-many-arguments diff --git a/src/agents/rail_car.cc b/src/agents/rail_car.cc index 61edbd5a3..54c58d1e0 100644 --- a/src/agents/rail_car.cc +++ b/src/agents/rail_car.cc @@ -22,6 +22,7 @@ #include #include #include +#include // public headers #include "delphyne/macros.h" @@ -31,6 +32,8 @@ #include "systems/rail_follower.h" #include "systems/rail_follower_params.h" #include "systems/rail_follower_state.h" +#include "systems/speed_system.h" +#include "systems/vector_source.h" /***************************************************************************** ** Namespaces @@ -127,6 +130,21 @@ std::unique_ptr RailCar::BuildDiagram() const { context_numeric_parameters)); rail_follower_system->set_name(name_ + "_system"); + vel_setter_ = builder.template AddSystem( + std::make_unique>(-1)); + + delphyne::SpeedSystem* speed_system = builder.AddSystem( + std::make_unique>()); + + builder.Connect(speed_system->acceleration_output(), + rail_follower_system->command_input()); + + builder.Connect(rail_follower_system->velocity_output(), + speed_system->feedback_input()); + + builder.Connect(vel_setter_->output(), + speed_system->command_input()); + /********************* * Diagram Outputs *********************/ @@ -137,4 +155,8 @@ std::unique_ptr RailCar::BuildDiagram() const { return std::move(builder.Build()); } +void RailCar::SetSpeed(double new_speed_mps) { + vel_setter_->Set(new_speed_mps); +} + } // namespace delphyne diff --git a/src/agents/rail_car.h b/src/agents/rail_car.h index 10105f457..2bcb20942 100644 --- a/src/agents/rail_car.h +++ b/src/agents/rail_car.h @@ -16,9 +16,12 @@ #include #include #include +#include // public headers #include "delphyne/mi6/agent_base.h" +#include "systems/speed_system.h" +#include "systems/vector_source.h" /***************************************************************************** ** Namespaces @@ -65,6 +68,12 @@ class RailCar : public delphyne::Agent { std::unique_ptr BuildDiagram() const; + /// + /// @brief Change the speed of this agent. + /// + /// @param new_speed_mps[in] The new speed for the agent in meters/second + void SetSpeed(double new_speed_mps); + private: // Container for the agent's initial configuration. // @@ -90,6 +99,8 @@ class RailCar : public delphyne::Agent { nominal_speed(nominal_speed) {} } initial_parameters_; + mutable delphyne::VectorSource* vel_setter_; + const drake::maliput::api::RoadGeometry& road_geometry_; }; diff --git a/src/backend/automotive_simulator.cc b/src/backend/automotive_simulator.cc index 81fc94fd6..7c2665917 100644 --- a/src/backend/automotive_simulator.cc +++ b/src/backend/automotive_simulator.cc @@ -112,12 +112,9 @@ std::unique_ptr AutomotiveSimulator::GetScene() { return std::move(scene_msg); } -// TODO(jwnimmer-tri): Modify the various vehicle model systems to be more -// uniform so common code from the following AddFooCar() methods can be moved -// into a shared method. - template -int AutomotiveSimulator::AddAgent(std::unique_ptr> agent) { +delphyne::AgentBase* AutomotiveSimulator::AddAgent( + std::unique_ptr> agent) { /********************* * Checks *********************/ @@ -167,7 +164,8 @@ int AutomotiveSimulator::AddAgent(std::unique_ptr> agent) { // save a handle to it agents_[id] = std::move(agent); - return id; + + return agents_[id].get(); } template @@ -180,22 +178,6 @@ const RoadGeometry* AutomotiveSimulator::SetRoadGeometry( return road_geometry_.get(); } -template -const delphyne::AgentBase& -AutomotiveSimulator::GetAgentById(int agent_id) const { - DELPHYNE_VALIDATE(agents_.count(agent_id) != 0, std::runtime_error, - "No agent found with the given ID."); - return *agents_.at(agent_id); -} - -template -delphyne::AgentBase* AutomotiveSimulator::GetMutableAgentById( - int agent_id) { - DELPHYNE_VALIDATE(agents_.count(agent_id) != 0, std::runtime_error, - "No agent found with the given ID."); - return agents_[agent_id].get(); -} - template void AutomotiveSimulator::GenerateAndLoadRoadNetworkUrdf() { std::string filename = road_geometry_->id().string(); @@ -240,8 +222,8 @@ struct IsSourceOf { } // namespace template -const std::vector> AutomotiveSimulator::GetCollisions() - const { +const std::vector*, delphyne::AgentBase*>> +AutomotiveSimulator::GetCollisions() { DELPHYNE_VALIDATE(has_started(), std::runtime_error, "Can only get collisions on a running simulation"); using drake::geometry::GeometryId; @@ -249,7 +231,8 @@ const std::vector> AutomotiveSimulator::GetCollisions() using drake::geometry::PenetrationAsPointPair; const std::vector> collisions = scene_query_->GetValue>().ComputePointPairPenetration(); - std::vector> agents_colliding; + std::vector*, delphyne::AgentBase*>> + agents_colliding; for (const auto& collision : collisions) { const auto it_A = std::find_if(agents_.begin(), agents_.end(), IsSourceOf(collision.id_A)); @@ -259,7 +242,8 @@ const std::vector> AutomotiveSimulator::GetCollisions() IsSourceOf(collision.id_B)); DELPHYNE_VALIDATE(it_B != agents_.end(), std::runtime_error, "Could not find second agent in list of agents"); - agents_colliding.emplace_back(it_A->first, it_B->first); + agents_colliding.emplace_back(agents_[it_A->first].get(), + agents_[it_B->first].get()); } return agents_colliding; } @@ -447,7 +431,7 @@ void AutomotiveSimulator::StepBy(const T& time_step) { } template -double AutomotiveSimulator::get_current_simulation_time() const { +double AutomotiveSimulator::GetCurrentSimulationTime() const { return drake::ExtractDoubleOrThrow(simulator_->get_context().get_time()); } @@ -477,6 +461,11 @@ PoseBundle AutomotiveSimulator::GetCurrentPoses() const { return pose_bundle; } +template +drake::systems::Context* AutomotiveSimulator::GetMutableContext() { + return &simulator_->get_mutable_context(); +} + template class AutomotiveSimulator; } // namespace delphyne diff --git a/src/backend/automotive_simulator.h b/src/backend/automotive_simulator.h index efcbce142..9135ea8e5 100644 --- a/src/backend/automotive_simulator.h +++ b/src/backend/automotive_simulator.h @@ -78,25 +78,8 @@ class AutomotiveSimulator { * @param[in] agent The user provided agent to add to the simulation. * @return A simulator generated unique id for the agent. */ - int AddAgent(std::unique_ptr> agent); - - /// Returns an immutable reference to the agent with the - /// given @p agent_id. - /// - /// @param[in] agent_id The ID of the agent, as returned - /// by AddAgent(). - /// @throw std::runtime_error if no agent with given ID - /// is known to to the simulator. - const delphyne::AgentBase& GetAgentById(int agent_id) const; - - /// Returns an mutable reference to the agent with the - /// given @p agent_id. - /// - /// @param[in] agent_id The ID of the agent, as returned - /// by AddAgent(). - /// @throw std::runtime_error if no agent with given ID - /// is known to to the simulator. - delphyne::AgentBase* GetMutableAgentById(int agent_id); + delphyne::AgentBase* AddAgent( + std::unique_ptr> agent); /// Sets the RoadGeometry for this simulation. /// @@ -113,7 +96,7 @@ class AutomotiveSimulator { /// Returns the System containing the entire AutomotiveSimulator diagram. /// /// @pre Build() has been called. - const drake::systems::System& GetDiagram() const { return *diagram_; } + const drake::systems::System* GetDiagram() const { return diagram_.get(); } /// Returns the current poses of all vehicles in the simulation. /// @@ -128,7 +111,8 @@ class AutomotiveSimulator { /// order. /// @pre Start() has been called. /// @throw std::runtime_error if any of the preconditions is not met. - const std::vector> GetCollisions() const; + const std::vector*, delphyne::AgentBase*>> + GetCollisions(); /// Calls Build() on the diagram (if it has not been build already) and /// initializes the Simulator. No further changes to the diagram may occur @@ -148,7 +132,9 @@ class AutomotiveSimulator { /// Returns the current simulation time in seconds. /// @see documentation of Simulator::Context::get_time. - double get_current_simulation_time() const; + double GetCurrentSimulationTime() const; + + drake::systems::Context* GetMutableContext(); private: // The rate at which the scene is published over ignition transport to diff --git a/src/backend/simulation_runner.cc b/src/backend/simulation_runner.cc index 4250411c3..e0924191a 100644 --- a/src/backend/simulation_runner.cc +++ b/src/backend/simulation_runner.cc @@ -217,10 +217,10 @@ void SimulatorRunner::RunInteractiveSimulationLoopFor( SetupNewRunStats(); - const double sim_end = simulator_->get_current_simulation_time() + duration; + const double sim_end = simulator_->GetCurrentSimulationTime() + duration; while (interactive_loop_running_ && - (simulator_->get_current_simulation_time() < sim_end)) { + (simulator_->GetCurrentSimulationTime() < sim_end)) { RunInteractiveSimulationLoopStep(); } @@ -278,8 +278,9 @@ void SimulatorRunner::RunInteractiveSimulationLoopStep() { // is not paused. if (collisions_enabled_ && !paused_) { // Computes collisions between agents. - const std::vector> agents_in_collision = - simulator_->GetCollisions(); + const std::vector< + std::pair*, delphyne::AgentBase*>> + agents_in_collision = simulator_->GetCollisions(); if (!agents_in_collision.empty()) { // Pauses simulation if necessary. PauseSimulation(); @@ -299,7 +300,7 @@ void SimulatorRunner::RunInteractiveSimulationLoopStep() { void SimulatorRunner::StepSimulationBy(double time_step) { simulator_->StepBy(time_step); - stats_.StepExecuted(simulator_->get_current_simulation_time()); + stats_.StepExecuted(simulator_->GetCurrentSimulationTime()); // Return if running at full speed if (realtime_rate_ == 0) { @@ -314,7 +315,7 @@ void SimulatorRunner::StepSimulationBy(double time_step) { } void SimulatorRunner::SetupNewRunStats() { - stats_.NewRunStartingAt(simulator_->get_current_simulation_time(), + stats_.NewRunStartingAt(simulator_->GetCurrentSimulationTime(), realtime_rate_); } diff --git a/src/backend/simulation_runner.h b/src/backend/simulation_runner.h index 8299dd23e..16779568b 100644 --- a/src/backend/simulation_runner.h +++ b/src/backend/simulation_runner.h @@ -113,8 +113,9 @@ class SimulatorRunner { public: // @brief On agent collision callback function type. // @see AutomotiveSimulator::GetCollisions() - using CollisionCallback = - std::function>&)>; + using CollisionCallback = std::function*, + delphyne::AgentBase*>>&)>; /// @brief Default constructor. /// @@ -285,8 +286,8 @@ class SimulatorRunner { void DisableCollisions() { collisions_enabled_ = false; } /// @brief Returns the current simulation time in seconds. - double get_current_simulation_time() const { - return simulator_->get_current_simulation_time(); + double GetCurrentSimulationTime() const { + return simulator_->GetCurrentSimulationTime(); } const delphyne::AutomotiveSimulator& GetSimulator() const { diff --git a/src/systems/speed_system.h b/src/systems/speed_system.h new file mode 100644 index 000000000..c22f7346b --- /dev/null +++ b/src/systems/speed_system.h @@ -0,0 +1,118 @@ +// Copyright 2018 Toyota Research Institute + +#pragma once + +#include +#include + +#include "delphyne/macros.h" + +namespace delphyne { + +/// The SpeedSystem implements a very simple speed controller, taking as an +/// input the current frame velocity (from an InputPort) and the desired speed +/// (from a second InputPort), and producing an acceleration on an OutputPort +/// to reach that speed. +template +class SpeedSystem final : public drake::systems::LeafSystem { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SpeedSystem) + + /// Default constructor. + SpeedSystem() { + speed_feedback_input_port_index_ = + this->DeclareVectorInputPort( + drake::systems::rendering::FrameVelocity()) + .get_index(); + + command_input_port_index_ = + this->DeclareVectorInputPort( + drake::systems::BasicVector(1)) + .get_index(); + + accel_output_port_index_ = + this->DeclareVectorOutputPort(drake::systems::BasicVector(1), + &SpeedSystem::CalcOutputAcceleration) + .get_index(); + } + + ~SpeedSystem() override {} + + const drake::systems::OutputPort& acceleration_output() const { + return this->get_output_port(accel_output_port_index_); + } + + const drake::systems::InputPort& feedback_input() const { + return this->get_input_port(speed_feedback_input_port_index_); + } + + const drake::systems::InputPort& command_input() const { + return this->get_input_port(command_input_port_index_); + } + + protected: + void CalcOutputAcceleration( + const drake::systems::Context& context, + drake::systems::BasicVector* output) const { + const drake::systems::rendering::FrameVelocity* feedback_input = + this->template EvalVectorInput< + drake::systems::rendering::FrameVelocity>( + context, speed_feedback_input_port_index_); + + if (feedback_input == nullptr) { + // If the feedback is not connected, we can't do anything, so leave + // acceleration at 0 + output->SetAtIndex(0, 0.0); + return; + } + + const drake::systems::BasicVector* cmd_input = + this->template EvalVectorInput( + context, command_input_port_index_); + + if (cmd_input == nullptr) { + // If the command input is not connected, we can't do anything, so leave + // acceleration at 0 + output->SetAtIndex(0, 0.0); + return; + } + + T cmd_speed = cmd_input->GetAtIndex(0); + + if (cmd_speed < 0.0) { + // If the input_speed is negative, that means we shouldn't do anything in + // this controller so we just set the acceleration to 0. + output->SetAtIndex(0, 0.0); + return; + } + + const drake::multibody::SpatialVelocity vel = + feedback_input->get_velocity(); + + // Let's calculate the magnitude of the vector to get an estimate + // of our forward speed. + T magnitude = vel.translational().norm(); + + if (cmd_speed > magnitude) { + output->SetAtIndex(0, kAccelerationSetPoint); + } else if (cmd_speed < magnitude) { + output->SetAtIndex(0, -kAccelerationSetPoint); + } else { + output->SetAtIndex(0, 0.0); + } + } + + private: + // The amount of acceleration that will be applied if the acceleration needs + // to be changed. + static constexpr T kAccelerationSetPoint = 10.0; + + /******************** + * System Indices + *******************/ + int speed_feedback_input_port_index_; + int accel_output_port_index_; + int command_input_port_index_; +}; + +} // namespace delphyne diff --git a/src/systems/vector_source.h b/src/systems/vector_source.h new file mode 100644 index 000000000..5ecbd9431 --- /dev/null +++ b/src/systems/vector_source.h @@ -0,0 +1,151 @@ +// Copyright 2018 Toyota Research Institute + +#pragma once + +#include +#include +#include +#include +#include + +#include +#include + +#include "delphyne/macros.h" + +namespace delphyne { + +// TODO(clalancette): We should allow VectorSource to be an N-vector, +// rather than just the 1-vector it is now. @stonier's idea here was +// to take a map of strings to indices in the constructor. The Set() +// method would then take a string and a value, look up the index based +// on the string, and set it to that value. + +/// The VectorSource is a drake system to continually set an output +/// port to a fixed value until the user decides to change it via the `Set` +/// API. At that point, the value will be (safely) updated to the new value, +/// and the ConstantVectorSettable will continue outputting that value until +/// the user asks for a new one. This differs from drake's ConstantVectorSource +/// in that it is thread-safe with respect to changes to the ConstantVector. +/// +/// @tparam T must be a valid Eigen ScalarType +template +class VectorSource final : public drake::systems::LeafSystem { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(VectorSource) + + explicit VectorSource(T defaultval) { + output_port_index_ = + this->DeclareVectorOutputPort(drake::systems::BasicVector(1), + &VectorSource::CalcOutputValue) + .get_index(); + this->DeclareAbstractState( + drake::systems::AbstractValue::Make(T{defaultval})); + val_ = defaultval; + } + + ~VectorSource() override {} + + /// Returns the value stored in @p context. + T Get(const drake::systems::Context& context) const { + const drake::systems::AbstractValues* abstract_state = + &context.get_abstract_state(); + + return abstract_state->get_value(kStateIndexVal).GetValue(); + } + + /// Sets a new value that will eventually be synchronized into @p context. + void Set(T new_val) { + std::lock_guard lock(mutex_); + val_ = new_val; + } + + const drake::systems::OutputPort& output() const { + return this->get_output_port(output_port_index_); + } + + protected: + void DoCalcNextUpdateTime(const drake::systems::Context& context, + drake::systems::CompositeEventCollection* events, + T* time) const override { + DELPHYNE_VALIDATE(events != nullptr, std::invalid_argument, + "Events pointer must not be null"); + DELPHYNE_VALIDATE(time != nullptr, std::invalid_argument, + "Time pointer must not be null"); + + // An update time calculation is required here to avoid having + // a NaN value when callling the StepBy method. + drake::systems::LeafSystem::DoCalcNextUpdateTime(context, events, time); + + const T last_val = Get(context); + + T curr_val; + { + std::lock_guard lock(mutex_); + curr_val = val_; + } + + // Has a new speed. Schedule an update event. + if (last_val != curr_val) { + // From Drake LCM implementation: + // TODO(siyuan): should be context.get_time() once #5725 is resolved. + *time = context.get_time() + 0.0001; + + drake::systems::EventCollection< + drake::systems::UnrestrictedUpdateEvent>& uu_events = + events->get_mutable_unrestricted_update_events(); + + uu_events.add_event( + std::make_unique>( + drake::systems::Event::TriggerType::kTimed)); + } + } + + void DoCalcUnrestrictedUpdate( + const drake::systems::Context& context, + const std::vector*>&, + drake::systems::State* state) const override { + DELPHYNE_VALIDATE(state != nullptr, std::invalid_argument, + "State pointer must not be null"); + + T curr_val; + { + std::lock_guard lock(mutex_); + curr_val = val_; + } + + drake::systems::AbstractValues* abstract_state = + &state->get_mutable_abstract_state(); + + abstract_state->get_mutable_value(kStateIndexVal).GetMutableValue() = + curr_val; + } + + void CalcOutputValue(const drake::systems::Context& context, + drake::systems::BasicVector* output) const { + const drake::systems::AbstractValues* abstract_state = + &context.get_abstract_state(); + + output->SetAtIndex(0, + abstract_state->get_value(kStateIndexVal).GetValue()); + } + + private: + mutable T val_; + + // The mutex that guards val_. + mutable std::mutex mutex_; + + // The index of the state used to access the internal value. + static constexpr int kStateIndexVal = 0; + + // The total number of states used by the system. + static constexpr int kTotalStateValues = 1; + + /******************** + * System Indices + *******************/ + int output_port_index_; +}; + +} // namespace delphyne diff --git a/test/regression/cpp/automotive_simulator_test.cc b/test/regression/cpp/automotive_simulator_test.cc index 8ae2773e7..204d21886 100644 --- a/test/regression/cpp/automotive_simulator_test.cc +++ b/test/regression/cpp/automotive_simulator_test.cc @@ -169,20 +169,6 @@ TEST_F(AutomotiveSimulatorTest, TestGetScene) { TEST_F(AutomotiveSimulatorTest, BasicTest) { auto simulator = std::make_unique>(); EXPECT_NE(nullptr, simulator->get_builder()); - - auto agent_bob = - std::make_unique("bob", 0.0, 0.0, 0.0, 0.0); - const int agent_bob_id = simulator->AddAgent(std::move(agent_bob)); - EXPECT_EQ(simulator->GetAgentById(agent_bob_id).name(), "bob"); - - auto agent_alice = - std::make_unique("alice", 0.0, 0.0, 0.0, 0.0); - const int agent_alice_id = simulator->AddAgent(std::move(agent_alice)); - EXPECT_EQ(simulator->GetAgentById(agent_alice_id).name(), "alice"); - - // Verifies that passing an unknown agent ID is an error. - const int agent_x_id = -1; - EXPECT_THROW(simulator->GetAgentById(agent_x_id), std::runtime_error); } // Covers simple-car, Start and StepBy @@ -192,9 +178,7 @@ TEST_F(AutomotiveSimulatorTest, TestPriusSimpleCar) { simulator->SetRoadGeometry(CreateDragway("TestDragway", 1)); auto agent = std::make_unique("bob", 0.0, 0.0, 0.0, 0.0); - const int id = simulator->AddAgent(std::move(agent)); - - EXPECT_EQ(id, 0); + simulator->AddAgent(std::move(agent)); // Finish all initialization, so that we can test the post-init state. simulator->Start(kRealtimeFactor); @@ -219,7 +203,7 @@ TEST_F(AutomotiveSimulatorTest, TestPriusSimpleCar) { test::IgnMonitor ign_monitor( kStateTopicName); - // Shortly after starting, we should have not have moved much. + // Shortly after starting, we should not have moved much. const int kStateMessagesCount{1}; EXPECT_TRUE(ign_monitor.do_until( kStateMessagesCount, kTimeoutMs, @@ -250,8 +234,7 @@ TEST_F(AutomotiveSimulatorTest, TestPriusSimpleCarInitialState) { auto agent = std::make_unique("bob", kX, kY, kHeading, kVelocity); - const int id = simulator->AddAgent(std::move(agent)); - EXPECT_EQ(id, 0); + simulator->AddAgent(std::move(agent)); // Set up a monitor to check for ignition::msgs::AgentState // messages coming from the agent. @@ -318,8 +301,7 @@ TEST_F(AutomotiveSimulatorTest, TestMobilControlledSimpleCar) { 0.0, // heading 10.0, // velocity *road_geometry); - const int id_mobil = simulator->AddAgent(std::move(mobil)); - EXPECT_EQ(0, id_mobil); + simulator->AddAgent(std::move(mobil)); auto decoy_1 = std::make_unique( "decoy1", *(road_geometry->junction(0)->segment(0)->lane(0)), @@ -329,8 +311,7 @@ TEST_F(AutomotiveSimulatorTest, TestMobilControlledSimpleCar) { 0.0, // speed (m) 0.0, // nominal_speed (m/s) *road_geometry); - const int id_decoy1 = simulator->AddAgent(std::move(decoy_1)); - EXPECT_EQ(1, id_decoy1); + simulator->AddAgent(std::move(decoy_1)); auto decoy_2 = std::make_unique( "decoy2", *(road_geometry->junction(0)->segment(0)->lane(0)), @@ -340,8 +321,7 @@ TEST_F(AutomotiveSimulatorTest, TestMobilControlledSimpleCar) { 0.0, // speed (m/s) 0.0, // nominal_speed (m/s) *road_geometry); - const int id_decoy2 = simulator->AddAgent(std::move(decoy_2)); - EXPECT_EQ(2, id_decoy2); + simulator->AddAgent(std::move(decoy_2)); // Setup an ignition transport topic monitor to listen to // ignition::msgs::Model_V messages being published to @@ -365,7 +345,7 @@ TEST_F(AutomotiveSimulatorTest, TestMobilControlledSimpleCar) { // Expect the SimpleCar to start steering to the left; y value increases. const double mobil_y = - draw_message.models(id_mobil).link(0).pose().position().y(); + draw_message.models(0).link(0).pose().position().y(); EXPECT_GE(mobil_y, -2.); } @@ -373,17 +353,6 @@ TEST_F(AutomotiveSimulatorTest, TestTrajectoryAgent) { auto simulator = std::make_unique>(); simulator->SetRoadGeometry(CreateDragway("TestDragway", 1)); - // std::vector times{0.0, 5.0, 10.0, 15.0, 20.0}; - // Eigen::Quaternion zero_heading( - // Eigen::AngleAxis(0.0, Eigen::Vector3d::UnitZ())); - // std::vector> orientations(5, zero_heading); - // std::vector translations{ - // Eigen::Vector3d(0.0, 0.00, 0.00), Eigen::Vector3d(10.0, 0.00, 0.00), - // Eigen::Vector3d(30.0, 0.00, 0.00), Eigen::Vector3d(60.0, 0.00, 0.00), - // Eigen::Vector3d(100.0, 0.00, 0.00)}; - // drake::automotive::AgentTrajectory trajectory = - // drake::automotive::AgentTrajectory::Make(times, orientations, - // translations); const double kPoseXTolerance{1e-6}; const double kTolerance{1e-8}; @@ -397,9 +366,7 @@ TEST_F(AutomotiveSimulatorTest, TestTrajectoryAgent) { std::make_unique("alice", times, headings, translations); - const int id = simulator->AddAgent(std::move(alice)); - - EXPECT_EQ(0, id); + simulator->AddAgent(std::move(alice)); // Setup an ignition transport topic monitor to listen to // ignition::msgs::Model_V messages being published to @@ -421,10 +388,10 @@ TEST_F(AutomotiveSimulatorTest, TestTrajectoryAgent) { EXPECT_EQ(GetLinkCount(draw_message), GetPriusLinkCount()); - auto alice_model = draw_message.models(id); + auto alice_model = draw_message.models(0); // Checks the car ids - EXPECT_EQ(alice_model.id(), id); + EXPECT_EQ(alice_model.id(), 0); auto link = alice_model.link(0); @@ -496,9 +463,7 @@ TEST_F(AutomotiveSimulatorTest, TestMaliputRailcar) { 0.0, // speed 0.0, // nominal_speed *road_geometry); - const int id = simulator->AddAgent(std::move(agent)); - - EXPECT_GE(id, 0); + simulator->AddAgent(std::move(agent)); // Setup an ignition transport topic monitor to listen to // ignition::msgs::Model_V messages being published to @@ -659,8 +624,8 @@ TEST_F(AutomotiveSimulatorTest, TestRailcarVelocityOutput) { 0.0, // nominal_speed *road_geometry); - int alice_id = simulator->AddAgent(std::move(alice)); - int bob_id = simulator->AddAgent(std::move(bob)); + simulator->AddAgent(std::move(alice)); + simulator->AddAgent(std::move(bob)); EXPECT_NO_THROW(simulator->Start()); @@ -676,8 +641,8 @@ TEST_F(AutomotiveSimulatorTest, TestRailcarVelocityOutput) { const drake::systems::rendering::PoseBundle poses = simulator->GetCurrentPoses(); ASSERT_EQ(poses.get_num_poses(), 2); - ASSERT_EQ(poses.get_model_instance_id(kAliceIndex), alice_id); - ASSERT_EQ(poses.get_model_instance_id(kBobIndex), bob_id); + ASSERT_EQ(poses.get_model_instance_id(kAliceIndex), 0); + ASSERT_EQ(poses.get_model_instance_id(kBobIndex), 1); EXPECT_FALSE(poses.get_velocity(kAliceIndex).get_value().isZero()); EXPECT_TRUE(poses.get_velocity(kBobIndex).get_value().isZero()); } @@ -773,7 +738,7 @@ TEST_F(AutomotiveSimulatorTest, TestGetCollisions) { auto agent_bob = std::make_unique( "bob", agent_bob_geo_position.x(), agent_bob_geo_position.y(), kHeadingEast, kCruiseSpeed); - simulator->AddAgent(std::move(agent_bob)); // Unused agent `Bob` id. + simulator->AddAgent(std::move(agent_bob)); // Configures agent `Alice`. const drake::maliput::api::LanePosition agent_alice_lane_position{ @@ -783,7 +748,7 @@ TEST_F(AutomotiveSimulatorTest, TestGetCollisions) { auto agent_alice = std::make_unique( "alice", agent_alice_geo_position.x(), agent_alice_geo_position.y(), kHeadingWest, kCruiseSpeed); - const int agent_alice_id = simulator->AddAgent(std::move(agent_alice)); + delphyne::AgentBase* alice_ptr = simulator->AddAgent(std::move(agent_alice)); // Configures agent `Smith`. const drake::maliput::api::LanePosition agent_smith_lane_position{ @@ -793,14 +758,14 @@ TEST_F(AutomotiveSimulatorTest, TestGetCollisions) { auto agent_smith = std::make_unique( "smith", agent_smith_geo_position.x(), agent_smith_geo_position.y(), kHeadingEast + kHeadingDeviation, kCruiseSpeed); - const int agent_smith_id = simulator->AddAgent(std::move(agent_smith)); + delphyne::AgentBase* smith_ptr = simulator->AddAgent(std::move(agent_smith)); // Finishes initialization and starts the simulation. simulator->Start(); // Verifies that no agent is in collision at the beginning // of the simulation. - std::vector> agent_pairs_in_collision = + std::vector*, delphyne::AgentBase*>> agent_pairs_in_collision = simulator->GetCollisions(); EXPECT_EQ(agent_pairs_in_collision.size(), 0); @@ -812,14 +777,13 @@ TEST_F(AutomotiveSimulatorTest, TestGetCollisions) { // agents are the expected ones. agent_pairs_in_collision = simulator->GetCollisions(); EXPECT_EQ(agent_pairs_in_collision.size(), 1); - const int first_colliding_agent_id = agent_pairs_in_collision[0].first; - const int second_colliding_agent_id = agent_pairs_in_collision[0].second; + + delphyne::AgentBase* coll1_ptr = agent_pairs_in_collision[0].first; + delphyne::AgentBase* coll2_ptr = agent_pairs_in_collision[0].second; // Cannot make any assumption regarding pair order, see // delphyne::AutomotiveSimulator::GetCollisions(). - EXPECT_TRUE((first_colliding_agent_id == agent_alice_id && - second_colliding_agent_id == agent_smith_id) || - (first_colliding_agent_id == agent_smith_id && - second_colliding_agent_id == agent_alice_id)); + EXPECT_TRUE((coll1_ptr == alice_ptr && coll2_ptr == smith_ptr) || + (coll1_ptr == smith_ptr && coll2_ptr == alice_ptr)); } ////////////////////////////////////////////////// diff --git a/test/regression/cpp/simulation_runner_test.cc b/test/regression/cpp/simulation_runner_test.cc index 6299b6564..760626459 100644 --- a/test/regression/cpp/simulation_runner_test.cc +++ b/test/regression/cpp/simulation_runner_test.cc @@ -307,7 +307,7 @@ TEST_F(SimulationRunnerTest, TestRunSyncFor) { sim_runner_->RunSyncFor(kDuration); // Compare simulation time - const auto elapsed_sim_time = sim_runner_->get_current_simulation_time(); + const auto elapsed_sim_time = sim_runner_->GetCurrentSimulationTime(); EXPECT_GE(elapsed_sim_time, kDuration * (1. - kRelativeTolerance)); EXPECT_LE(elapsed_sim_time, kDuration * (1. + kRelativeTolerance)); @@ -342,7 +342,7 @@ TEST_F(SimulationRunnerTest, TestRunAsyncFor) { } // Compare simulation time - const auto elapsed_sim_time = sim_runner_->get_current_simulation_time(); + const auto elapsed_sim_time = sim_runner_->GetCurrentSimulationTime(); EXPECT_GE(elapsed_sim_time, kDuration * (1. - kRelativeTolerance)); EXPECT_LE(elapsed_sim_time, kDuration * (1. + kRelativeTolerance)); @@ -410,7 +410,7 @@ TEST_F(SimulationRunnerTest, TestPlayPauseOnRunAsyncFor) { EXPECT_LE(wall_clock_duration, max_wall_clock_time); // Compare simulation time - const auto elapsed_sim_time = sim_runner_->get_current_simulation_time(); + const auto elapsed_sim_time = sim_runner_->GetCurrentSimulationTime(); EXPECT_GE(elapsed_sim_time, kSimulationDuration * (1. - kSimulationRelativeTolerance));