Skip to content

Commit

Permalink
fix a few win warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
ahoarau committed Sep 30, 2018
1 parent 5007f08 commit 85ba319
Show file tree
Hide file tree
Showing 9 changed files with 129 additions and 135 deletions.
32 changes: 14 additions & 18 deletions include/orca/gazebo/Utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,6 @@
//| The fact that you are presently reading this means that you have had
//| knowledge of the CeCILL-C license and that you accept its terms.

#pragma once
#if defined(_WIN32) && !defined(_ENABLE_EXTENDED_ALIGNED_STORAGE)
#define _ENABLE_EXTENDED_ALIGNED_STORAGE
#endif
#include <Eigen/Geometry>
#include <ignition/math/Vector3.hh>
#include <ignition/math/Quaternion.hh>
Expand Down Expand Up @@ -145,8 +141,8 @@ namespace gazebo
/**
* \class GazeboWrenchSensor
* \brief A Wrench sensor w.r.t. a base_link. Wrench is expressed from the world to the body, in the base_link frame.
*
* This class is a wrapper to a ForceTorqueSensor or ContactSensor to store frame information.
*
* This class is a wrapper to a ForceTorqueSensor or ContactSensor to store frame information.
* Indeed there is no easy way to get the attributes of the Gazebo sensor.
*/
class GazeboWrenchSensor
Expand All @@ -157,10 +153,10 @@ class GazeboWrenchSensor

virtual ~GazeboWrenchSensor()
{}

protected:
GazeboWrenchSensor(const std::string& base_link)
: base_link_(base_link)
: base_link_(base_link)
{}

public:
Expand All @@ -185,7 +181,7 @@ class GazeboWrenchSensor
{
connection_ptr_ = conn_ptr;
}

/**
* \brief sets the wrench in the base_link frame
* \warning the input wrench should be in the base_link frame, from the world to the body
Expand All @@ -194,7 +190,7 @@ class GazeboWrenchSensor
{
wrench_ = wrench;
}

Eigen::Matrix<double,6,1>& wrench()
{
return wrench_;
Expand Down Expand Up @@ -226,7 +222,7 @@ class GazeboForceTorqueSensor : public GazeboWrenchSensor
sensor_->ConnectUpdate(subscriber)
);
}

/**
* \brief sets the ForceTorqueSensorPtr to connect to
* \warning the ForceTorqueSensorPtr should be with attributes <measure_direction>child_to_parent</measure_direction> <frame>child</frame>
Expand All @@ -235,12 +231,12 @@ class GazeboForceTorqueSensor : public GazeboWrenchSensor
{
sensor_ = sensor;
}

::gazebo::sensors::ForceTorqueSensorPtr getSensor() const
{
return sensor_;
}

void setWrenchFrom(const ::gazebo::msgs::WrenchStamped& wrench_stamped)
{
gazeboMsgToEigen(wrench_stamped, wrench());
Expand All @@ -265,7 +261,7 @@ class GazeboContactSensor : public GazeboWrenchSensor
sensor_->ConnectUpdated(subscriber)
);
}

const std::string& getCollisionName() const
{
return collision_;
Expand All @@ -278,7 +274,7 @@ class GazeboContactSensor : public GazeboWrenchSensor
{
sensor_ = sensor;
}

::gazebo::sensors::ContactSensorPtr getSensor() const
{
return sensor_;
Expand All @@ -288,7 +284,7 @@ class GazeboContactSensor : public GazeboWrenchSensor
{
return link_;
}

void setWrenchFrom( void )
{
/**
Expand Down Expand Up @@ -322,7 +318,7 @@ class GazeboContactSensor : public GazeboWrenchSensor
wrench_res_atCoG_inLink.head<3>() += convVec3(contacts.contact(i).wrench(j).body_2_wrench().force());
wrench_res_atCoG_inLink.tail<3>() += convVec3(contacts.contact(i).wrench(j).body_2_wrench().torque());
}
else
else
throw std::runtime_error("Mismatching collision bodies names");
}
}
Expand All @@ -333,7 +329,7 @@ class GazeboContactSensor : public GazeboWrenchSensor
::gazebo::sensors::ContactSensorPtr sensor_ = nullptr;
::gazebo::physics::LinkPtr link_ = nullptr;
std::string collision_;
}; // GazeboContactSensor
}; // GazeboContactSensor


} // namespace gazebo
Expand Down
5 changes: 4 additions & 1 deletion include/orca/math/WeightedEuclidianNormFunction.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,13 @@ class WeightedEuclidianNormFunction : public AffineFunction
{
public:
WeightedEuclidianNormFunction();

virtual ~WeightedEuclidianNormFunction() {}

class QuadraticCost
{
public:
virtual ~QuadraticCost() {}

void resize(int A_or_b_rows);

Size getSize() const;
Expand Down
2 changes: 1 addition & 1 deletion include/orca/optim/QPSolver.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class QPSolver
bool solve(orca::optim::ProblemData& data);
common::ReturnCode getReturnCode() const;
private:
std::unique_ptr<QPSolverImpl> pimpl_;
std::shared_ptr<QPSolverImpl> pimpl_;
common::ReturnCode ret_ = common::ReturnCode::RET_INIT_FAILED;
int nvar_ = 0;
int nconstr_ = 0;
Expand Down
8 changes: 4 additions & 4 deletions include/orca/robot/RobotModel.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,13 +289,13 @@ class RobotModel : public common::ConfigurableOrcaObject
common::Parameter<Eigen::Vector3d> gravity_;
common::Parameter<Eigen::VectorXd> home_joint_positions_;
common::Parameter<std::string> name_;

bool loadFromParameters();
private:

template<RobotModelImplType type = iDynTree> class RobotModelImpl;
std::unique_ptr<RobotModelImpl<> > impl_;
std::shared_ptr<RobotModelImpl<> > impl_;

};

} // namespace robot
Expand Down
56 changes: 25 additions & 31 deletions include/orca/utils/Logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,43 +35,38 @@
//| knowledge of the CeCILL-C license and that you accept its terms.

#pragma once

#include <plog/Log.h>


namespace orca
{
namespace utils
{
namespace utils
{

enum class LogLevel
{
none = 0,
fatal = 1,
error = 2,
warning = 3,
info = 4,
debug = 5,
verbose = 6
};
enum class LogLevel
{
none = 0,
fatal = 1,
error = 2,
warning = 3,
info = 4,
debug = 5,
verbose = 6
};

struct Logger
{
Logger();
static void setLogLevel(LogLevel log_level);
static void setLogLevel(int log_level);
static void setLogLevel(const std::string& log_level);
static void parseArgv(int argc,char ** argv);
static void parseArgv(const std::vector<std::string>& v);
static void parseArgv(int argc,char const* argv[]);
};
}
}
struct Logger
{
Logger();
virtual ~Logger() {}
static void setLogLevel(LogLevel log_level);
static void setLogLevel(int log_level);
static void setLogLevel(const std::string& log_level);
static void parseArgv(int argc,char ** argv);
static void parseArgv(const std::vector<std::string>& v);
static void parseArgv(int argc,char const* argv[]);
};
} // namespace utils
} // namespace orca

#ifdef _WIN32
#if defined(_WIN32) && !defined(_ENABLE_EXTENDED_ALIGNED_STORAGE)
#define _ENABLE_EXTENDED_ALIGNED_STORAGE
#endif
#include <Eigen/Dense>
#include <sstream>
namespace plog
Expand All @@ -91,4 +86,3 @@ namespace plog
return record << ss.str();
}
}
#endif
5 changes: 0 additions & 5 deletions include/orca/utils/Utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,6 @@

#pragma once
#include <iostream>
#if defined(_WIN32) && !defined(_ENABLE_EXTENDED_ALIGNED_STORAGE)
#define _ENABLE_EXTENDED_ALIGNED_STORAGE
#endif
#include <Eigen/Dense>
#include <memory>
#include <cstdlib>
Expand All @@ -52,8 +49,6 @@
#include <map>
#include "orca/utils/Logger.h"

#define UNUSED(expr) (void)(expr)

namespace orca
{
namespace utils
Expand Down
3 changes: 0 additions & 3 deletions src/optim/QPSolverImpl_osqp.impl
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
#include "orca/optim/QPSolverImpl.h"
#include "orca/utils/Logger.h"
#include <osqp.h>
#if defined(_WIN32) && !defined(_ENABLE_EXTENDED_ALIGNED_STORAGE)
#define _ENABLE_EXTENDED_ALIGNED_STORAGE
#endif
#include <Eigen/Dense>
#include <Eigen/Sparse>
#include <iostream>
Expand Down
2 changes: 1 addition & 1 deletion src/optim/QPSolverImpl_qpOASES.impl
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace optim
class QPSolverImpl_qpOASES : public QPSolverImpl
{
private:
std::unique_ptr<qpOASES::SQProblem> qpoases_;
std::shared_ptr<qpOASES::SQProblem> qpoases_;
qpOASES::Options options_;
bool qpoases_initialized_ = false;
public:
Expand Down

0 comments on commit 85ba319

Please sign in to comment.