Skip to content

Commit

Permalink
Addressed comments from Michel
Browse files Browse the repository at this point in the history
  • Loading branch information
Alexis Pojomovsky committed Jul 12, 2018
1 parent 2fa50f9 commit 1b4f971
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 70 deletions.
8 changes: 4 additions & 4 deletions src/backend/automotive_simulator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -177,8 +177,8 @@ const RoadGeometry* AutomotiveSimulator<T>::SetRoadGeometry(
}

template <typename T>
const delphyne::AgentBase<T>& AutomotiveSimulator<T>::GetAgentById(
int agent_id) const {
const delphyne::AgentBase<T>&
AutomotiveSimulator<T>::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);
Expand Down Expand Up @@ -348,9 +348,9 @@ void AutomotiveSimulator<T>::Build() {
// Connects the PoseBundleToSimpleCarState_v input and output.
builder_->Connect(
aggregator_->get_output_port(0),
pose_bundle_to_simple_car_state_v_->get_pose_bundle_input_port());
pose_bundle_to_simple_car_state_v_->get_input_port(0));
builder_->Connect(
pose_bundle_to_simple_car_state_v_->get_simple_car_state_v_output(),
pose_bundle_to_simple_car_state_v_->get_output_port(0),
agents_state_publisher_system->get_input_port(0));

diagram_ = builder_->Build();
Expand Down
52 changes: 18 additions & 34 deletions src/translations/pose_bundle_to_simple_car_state_v.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,55 +8,39 @@
#include <drake/systems/rendering/pose_bundle.h>

#include "delphyne/protobuf/simple_car_state_v.pb.h"
#include "delphyne/protobuf/simple_car_state.pb.h"
#include "translations/drake_to_ign.h"

namespace delphyne {

using drake::systems::rendering::PoseBundle;
const unsigned int kPoseBundleVectorSize{0};

PoseBundleToSimpleCarState_V::PoseBundleToSimpleCarState_V() {
const int kPoseBundleVectorSize{0};
// Declares input ports.
pose_bundle_input_port_index_ =
this->DeclareInputPort(drake::systems::kVectorValued,
kPoseBundleVectorSize)
.get_index();
// Declares output port.
output_port_index_ =
this->DeclareAbstractOutputPort(
&PoseBundleToSimpleCarState_V::CalcSimpleCarState_V)
.get_index();
}

void PoseBundleToSimpleCarState_V::CalcSimpleCarState_V(
const drake::systems::Context<double>& context,
ignition::msgs::SimpleCarState_V* output) const {
// Obtains the input and output.
const PoseBundle<double>& pose_bundle =
drake::systems::System<double>::EvalAbstractInput(
context, pose_bundle_input_port_index_)
->template GetValue<PoseBundle<double>>();
void PoseBundleToSimpleCarState_V::DoDrakeToIgnTranslation(
const drake::systems::rendering::PoseBundle<double>& drake_message,
ignition::msgs::SimpleCarState_V* ign_message, int64_t time_ms) const {

// Clears the current SimpleCarState_V message from its previous content.
output->Clear();
// Clears state from the previous call.
// @see DrakeToIgn::DoDrakeToIgnTranslation
ign_message->Clear();

for (int i = 0; i < pose_bundle.get_num_poses(); ++i) {
for (int i = 0; i < drake_message.get_num_poses(); ++i) {
// Gets the car's pose.
const drake::Isometry3<double>& pose = pose_bundle.get_pose(i);
const drake::Isometry3<double>& pose = drake_message.get_pose(i);
// Translates pose from quaternion to euler.
const Eigen::Vector3d& euler_rotation =
const Eigen::Vector3d euler_rotation =
pose.rotation().eulerAngles(0, 1, 2);

// Calculates car's velocity.
const drake::systems::rendering::FrameVelocity<double>& velocity =
pose_bundle.get_velocity(i);
const drake::multibody::SpatialVelocity<double>& spatial_velocity =
const drake::systems::rendering::FrameVelocity<double> velocity =
drake_message.get_velocity(i);
const drake::multibody::SpatialVelocity<double> spatial_velocity =
velocity.get_velocity();
const double& velocity_norm =
const double velocity_norm =
static_cast<double>(spatial_velocity.translational().norm());

// Appends a new state to the vector.
auto* current_state = output->add_states();
current_state->set_name("/agent/" + pose_bundle.get_name(i) + "/state");
ignition::msgs::SimpleCarState* current_state = ign_message->add_states();
current_state->set_name("/agent/" + drake_message.get_name(i) + "/state");
current_state->set_x(pose.translation().x());
current_state->set_y(pose.translation().y());
current_state->set_heading(euler_rotation(2));
Expand Down
41 changes: 12 additions & 29 deletions src/translations/pose_bundle_to_simple_car_state_v.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,43 +2,26 @@

#pragma once

#include <drake/systems/framework/leaf_system.h>
#include <drake/systems/rendering/pose_bundle.h>

#include <ignition/msgs.hh>

#include "delphyne/protobuf/simple_car_state.pb.h"
#include "delphyne/protobuf/simple_car_state_v.pb.h"
#include "translations/drake_to_ign.h"

namespace delphyne {

/// @brief A system that takes a PoseBundle and generates an array of
/// SimpleCarStates (SimpleCarState_V).
class PoseBundleToSimpleCarState_V : public drake::systems::LeafSystem<double> {
public:
PoseBundleToSimpleCarState_V();

/// @brief Returns the output port of the system.
const drake::systems::OutputPort<double>& get_simple_car_state_v_output()
const {
return this->get_output_port(output_port_index_);
}

/// @brief Returns the input port descriptor for the pose bundle. This port
/// expects a drake::sytems::rendering::PoseBundle<double>.
const drake::systems::InputPortDescriptor<double>&
get_pose_bundle_input_port() const {
return get_input_port(pose_bundle_input_port_index_);
}

class PoseBundleToSimpleCarState_V
: public DrakeToIgn<drake::systems::rendering::PoseBundle<double>,
ignition::msgs::SimpleCarState_V> {
protected:
/// @brief Calculates the SimpleCarState_V message based on the given context.
void CalcSimpleCarState_V(const drake::systems::Context<double>& context,
ignition::msgs::SimpleCarState_V* output) const;

private:
// @brief The pose bundle input port index assigned by the system.
int pose_bundle_input_port_index_{};

// @brief The abstract output port index assigned by the system.
int output_port_index_{};
// @brief @see DrakeToIgn::DoDrakeToIgnTranslation.
void DoDrakeToIgnTranslation(
const drake::systems::rendering::PoseBundle<double>& drake_message,
ignition::msgs::SimpleCarState_V* ign_message,
int64_t time_ms) const override;
};

} // namespace delphyne
11 changes: 8 additions & 3 deletions test/regression/cpp/automotive_simulator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -225,6 +225,8 @@ TEST_F(AutomotiveSimulatorTest, TestPriusSimpleCar) {
kStateMessagesCount, kTimeoutMs,
[this, &simulator]() { simulator->StepBy(kSmallTimeStep); }));

EXPECT_TRUE(ign_monitor.get_last_message().states_size() > 0);

ignition::msgs::SimpleCarState state_message =
ign_monitor.get_last_message().states(0);
EXPECT_LT(state_message.x(), 0.1);
Expand Down Expand Up @@ -264,12 +266,15 @@ TEST_F(AutomotiveSimulatorTest, TestPriusSimpleCarInitialState) {
kStateMessagesCount, kTimeoutMs,
[this, &simulator]() { simulator->StepBy(kSmallTimeStep); }));


EXPECT_TRUE(ign_monitor.get_last_message().states_size() > 0);

const ignition::msgs::SimpleCarState state_message =
ign_monitor.get_last_message().states(0);

// A very minimal loss of accuracy is produced during the conversion from the
// PoseBundle to the SimpleCarState. Hence, a small tolerance is allowed when
// comparing the values from the SimpleCarState with the expected values.
// Computations of SimpleCarState from a PoseBundle incur minimal numerical
// precision loss. Hence, a small tolerance is allowed when comparing the
// values from the SimpleCarState with the expected values.
const double kAccuracy = 1e-15;

EXPECT_EQ(state_message.x(), kX);
Expand Down

0 comments on commit 1b4f971

Please sign in to comment.