Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#6035 from jwnimmer-tri/build-unuse…
Browse files Browse the repository at this point in the history
…d-parameter-rbp

Fix Wunused-parameter in rigid_body_plant
  • Loading branch information
sherm1 authored May 5, 2017
2 parents dc9af67 + fb78288 commit d354bdc
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 13 deletions.
6 changes: 3 additions & 3 deletions drake/multibody/rigid_body_plant/drake_visualizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ class DrakeVisualizer : public LeafSystem<double> {
}

// Set the default to "initialization phase has not been completed."
void SetDefaultState(const Context<double>& context, State<double>* state)
void SetDefaultState(const Context<double>&, State<double>* state)
const override {
set_is_load_message_sent(state->get_mutable_discrete_state(), false);
}
Expand All @@ -141,8 +141,8 @@ class DrakeVisualizer : public LeafSystem<double> {
const Context<double>& context,
DiscreteValues<double>* discrete_state) const override;

void DoCalcOutput(const systems::Context<double>& context,
systems::SystemOutput<double>* output) const override {}
void DoCalcOutput(const systems::Context<double>&,
systems::SystemOutput<double>*) const override {}

// Publishes a draw message if initialization is completed. Otherwise, it
// emits a warning and return.
Expand Down
5 changes: 2 additions & 3 deletions drake/multibody/rigid_body_plant/rigid_body_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -160,9 +160,8 @@ void RigidBodyPlant<T>::set_friction_contact_parameters(
}

template <typename T>
bool RigidBodyPlant<T>::DoHasDirectFeedthrough(const SparsityMatrix* sparsity,
int input_port,
int output_port) const {
bool RigidBodyPlant<T>::DoHasDirectFeedthrough(const SparsityMatrix*, int, int)
const {
return false;
}

Expand Down
10 changes: 5 additions & 5 deletions drake/multibody/rigid_body_plant/rigid_body_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,7 @@ class RigidBodyPlant : public LeafSystem<T> {
/// Sets the state in `context` so that generalized positions and velocities
/// are zero. For quaternion based joints the quaternion is set to be the
/// identity (or equivalently a zero rotation).
void SetDefaultState(const Context<T>& context,
void SetDefaultState(const Context<T>&,
State<T>* state) const override {
DRAKE_DEMAND(state != nullptr);

Expand Down Expand Up @@ -363,19 +363,19 @@ class RigidBodyPlant : public LeafSystem<T> {
// TODO(amcastro-tri): provide proper implementations for these methods to
// track energy conservation.
// TODO(amcastro-tri): provide a method to track applied actuator power.
T DoCalcPotentialEnergy(const Context<T>& context) const override {
T DoCalcPotentialEnergy(const Context<T>&) const override {
return T(NAN);
}

T DoCalcKineticEnergy(const Context<T>& context) const override {
T DoCalcKineticEnergy(const Context<T>&) const override {
return T(NAN);
}

T DoCalcConservativePower(const Context<T>& context) const override {
T DoCalcConservativePower(const Context<T>&) const override {
return T(NAN);
}

T DoCalcNonConservativePower(const Context<T>& context) const override {
T DoCalcNonConservativePower(const Context<T>&) const override {
return T(NAN);
}

Expand Down
3 changes: 1 addition & 2 deletions drake/multibody/rigid_body_plant/viewer_draw_translator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@ ViewerDrawTranslator::ViewerDrawTranslator(
}

void ViewerDrawTranslator::Deserialize(
const void* lcm_message_bytes, int lcm_message_length,
VectorBase<double>* vector_base) const {
const void*, int, VectorBase<double>*) const {
DRAKE_ABORT_MSG(
"The translator that converts from a drake::lcmt_viewer_draw message to "
"a VectorBase object that contains the RigidBodyTree's state vector has not"
Expand Down

0 comments on commit d354bdc

Please sign in to comment.