Skip to content
This repository has been archived by the owner on Oct 26, 2018. It is now read-only.

Commit

Permalink
Suppport for MSVC DLLs.
Browse files Browse the repository at this point in the history
Change-Id: Ibbcc4ba4e59f5bbf1cb91fe81c7d3b9042d03493
  • Loading branch information
bjornpiltz authored and keir committed Apr 28, 2014
1 parent c830820 commit 5d7eed8
Show file tree
Hide file tree
Showing 17 changed files with 108 additions and 73 deletions.
12 changes: 12 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,17 @@ OPTION(BUILD_SHARED_LIBS "Build Ceres as a shared library." OFF)
IF (MSVC)
OPTION(MSVC_USE_STATIC_CRT
"MS Visual Studio: Use static C-Run Time Library in place of shared." OFF)

IF ( BUILD_TESTING AND BUILD_SHARED_LIBS)
MESSAGE(
"-- Disabling tests. The flags BUILD_TESTING and BUILD_SHARED_LIBS"
" are incompatible with MSVC."
)
# Retain the help string associated with the BUILD_TESTING option
# and turn testing off.
GET_PROPERTY(HELP_STRING CACHE BUILD_TESTING PROPERTY HELPSTRING)
SET(BUILD_TESTING OFF CACHE BOOL "${HELP_STRING}" FORCE)
ENDIF (BUILD_TESTING AND BUILD_SHARED_LIBS)
ENDIF (MSVC)

# Prior to October 2013, Ceres used some non-CMake standardised variables to
Expand Down Expand Up @@ -474,6 +485,7 @@ ENDIF (GFLAGS)

IF (BUILD_SHARED_LIBS)
MESSAGE("-- Building Ceres as a shared library.")
ADD_DEFINITIONS(-DCERES_BUILDING_SHARED_LIBRARY)
ELSE (BUILD_SHARED_LIBS)
MESSAGE("-- Building Ceres as a static library.")
ENDIF (BUILD_SHARED_LIBS)
Expand Down
4 changes: 3 additions & 1 deletion docs/source/building.rst
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,9 @@ Notes:

#. The default build is Debug; consider switching it to release mode.
#. Currently ``system_test`` is not working properly.
#. Building Ceres as a DLL is not supported; patches welcome.
#. If you build Ceres as a DLL with Visual Studio (BUILD_SHARED_LIBS),
you have to compile your own code with the flag
CERES_USING_SHARED_LIBRARY.
#. CMake puts the resulting test binaries in ``ceres-bin/examples/Debug``
by default.
#. The solvers supported on Windows are ``DENSE_QR``, ``DENSE_SCHUR``,
Expand Down
4 changes: 4 additions & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,10 @@
#
# Author: [email protected] (Keir Mierle)

IF (BUILD_SHARED_LIBS)
ADD_DEFINITIONS(-DCERES_USING_SHARED_LIBRARY)
ENDIF()

ADD_EXECUTABLE(helloworld helloworld.cc)
TARGET_LINK_LIBRARIES(helloworld ceres)

Expand Down
30 changes: 16 additions & 14 deletions include/ceres/c_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,14 @@
#ifndef CERES_PUBLIC_C_API_H_
#define CERES_PUBLIC_C_API_H_

#include "ceres/internal/port.h"

#ifdef __cplusplus
extern "C" {
#endif

/* Init the Ceres private data. Must be called before anything else. */
void ceres_init();
CERES_EXPORT void ceres_init();

/* Equivalent to CostFunction::Evaluate() in the C++ API.
*
Expand Down Expand Up @@ -88,23 +90,23 @@ typedef void (*ceres_loss_function_t)(void* user_data,
*
* See loss_function.h for the details of each loss function.
*/
void* ceres_create_huber_loss_function_data(double a);
void* ceres_create_softl1_loss_function_data(double a);
void* ceres_create_cauchy_loss_function_data(double a);
void* ceres_create_arctan_loss_function_data(double a);
void* ceres_create_tolerant_loss_function_data(double a, double b);
CERES_EXPORT void* ceres_create_huber_loss_function_data(double a);
CERES_EXPORT void* ceres_create_softl1_loss_function_data(double a);
CERES_EXPORT void* ceres_create_cauchy_loss_function_data(double a);
CERES_EXPORT void* ceres_create_arctan_loss_function_data(double a);
CERES_EXPORT void* ceres_create_tolerant_loss_function_data(double a, double b);

/* Free the given stock loss function data. */
void ceres_free_stock_loss_function_data(void* loss_function_data);
CERES_EXPORT void ceres_free_stock_loss_function_data(void* loss_function_data);

/* This is an implementation of ceres_loss_function_t contained within Ceres
* itself, intended as a way to access the various stock Ceres loss functions
* from the C API. This should be passed to ceres_add_residual() below, in
* combination with a user_data pointer generated by
* ceres_create_stock_loss_function() above. */
void ceres_stock_loss_function(void* user_data,
double squared_norm,
double out[3]);
CERES_EXPORT void ceres_stock_loss_function(void* user_data,
double squared_norm,
double out[3]);

/* Equivalent to Problem from the C++ API. */
struct ceres_problem_s;
Expand All @@ -115,11 +117,11 @@ typedef struct ceres_residual_block_id_s ceres_residual_block_id_t;

/* Create and destroy a problem */
/* TODO(keir): Add options for the problem. */
ceres_problem_t* ceres_create_problem();
void ceres_free_problem(ceres_problem_t* problem);
CERES_EXPORT ceres_problem_t* ceres_create_problem();
CERES_EXPORT void ceres_free_problem(ceres_problem_t* problem);

/* Add a residual block. */
ceres_residual_block_id_t* ceres_problem_add_residual_block(
CERES_EXPORT ceres_residual_block_id_t* ceres_problem_add_residual_block(
ceres_problem_t* problem,
ceres_cost_function_t cost_function,
void* cost_function_data,
Expand All @@ -130,7 +132,7 @@ ceres_residual_block_id_t* ceres_problem_add_residual_block(
int* parameter_block_sizes,
double** parameters);

void ceres_solve(ceres_problem_t* problem);
CERES_EXPORT void ceres_solve(ceres_problem_t* problem);

/* TODO(keir): Figure out a way to pass a config in. */

Expand Down
2 changes: 1 addition & 1 deletion include/ceres/conditioned_cost_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace ceres {
// ccf_residual[i] = f_i(my_cost_function_residual[i])
//
// and the Jacobian will be affected appropriately.
class ConditionedCostFunction : public CostFunction {
class CERES_EXPORT ConditionedCostFunction : public CostFunction {
public:
// Builds a cost function based on a wrapped cost function, and a
// per-residual conditioner. Takes ownership of all of the wrapped cost
Expand Down
2 changes: 1 addition & 1 deletion include/ceres/cost_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace ceres {
// code inheriting from this class is expected to set these two members with the
// corresponding accessors. This information will be verified by the Problem
// when added with AddResidualBlock().
class CostFunction {
class CERES_EXPORT CostFunction {
public:
CostFunction() : num_residuals_(0) {}

Expand Down
4 changes: 2 additions & 2 deletions include/ceres/covariance.h
Original file line number Diff line number Diff line change
Expand Up @@ -196,9 +196,9 @@ class CovarianceImpl;
// covariance.GetCovarianceBlock(y, y, covariance_yy)
// covariance.GetCovarianceBlock(x, y, covariance_xy)
//
class Covariance {
class CERES_EXPORT Covariance {
public:
struct Options {
struct CERES_EXPORT Options {
Options()
#ifndef CERES_NO_SUITESPARSE
: algorithm_type(SPARSE_QR),
Expand Down
2 changes: 1 addition & 1 deletion include/ceres/crs_matrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ namespace ceres {

// A compressed row sparse matrix used primarily for communicating the
// Jacobian matrix to the user.
struct CRSMatrix {
struct CERES_EXPORT CRSMatrix {
CRSMatrix() : num_rows(0), num_cols(0) {}

int num_rows;
Expand Down
15 changes: 15 additions & 0 deletions include/ceres/internal/port.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,9 @@
#ifndef CERES_PUBLIC_INTERNAL_PORT_H_
#define CERES_PUBLIC_INTERNAL_PORT_H_

// This file needs to compile as c code.
#ifdef __cplusplus

#include <string>

#if defined(CERES_TR1_MEMORY_HEADER)
Expand Down Expand Up @@ -59,4 +62,16 @@ using std::shared_ptr;

} // namespace ceres

#endif // __cplusplus

// A macro to signal wich functions and classes are exported when
// bulding a DLL with MSC.
#if defined(_MSC_VER) && defined(CERES_USING_SHARED_LIBRARY)
# define CERES_EXPORT __declspec(dllimport)
#elif defined(_MSC_VER) && defined(CERES_BUILDING_SHARED_LIBRARY)
# define CERES_EXPORT __declspec(dllexport)
#else
# define CERES_EXPORT
#endif

#endif // CERES_PUBLIC_INTERNAL_PORT_H_
4 changes: 2 additions & 2 deletions include/ceres/iteration_callback.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ namespace ceres {

// This struct describes the state of the optimizer after each
// iteration of the minimization.
struct IterationSummary {
struct CERES_EXPORT IterationSummary {
IterationSummary()
: iteration(0),
step_is_valid(false),
Expand Down Expand Up @@ -211,7 +211,7 @@ struct IterationSummary {
// const bool log_to_stdout_;
// };
//
class IterationCallback {
class CERES_EXPORT IterationCallback {
public:
virtual ~IterationCallback() {}
virtual CallbackReturnType operator()(const IterationSummary& summary) = 0;
Expand Down
8 changes: 4 additions & 4 deletions include/ceres/local_parameterization.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ namespace ceres {
//
// The class LocalParameterization defines the function Plus and its
// Jacobian which is needed to compute the Jacobian of f w.r.t delta.
class LocalParameterization {
class CERES_EXPORT LocalParameterization {
public:
virtual ~LocalParameterization() {}

Expand All @@ -133,7 +133,7 @@ class LocalParameterization {
// Some basic parameterizations

// Identity Parameterization: Plus(x, delta) = x + delta
class IdentityParameterization : public LocalParameterization {
class CERES_EXPORT IdentityParameterization : public LocalParameterization {
public:
explicit IdentityParameterization(int size);
virtual ~IdentityParameterization() {}
Expand All @@ -150,7 +150,7 @@ class IdentityParameterization : public LocalParameterization {
};

// Hold a subset of the parameters inside a parameter block constant.
class SubsetParameterization : public LocalParameterization {
class CERES_EXPORT SubsetParameterization : public LocalParameterization {
public:
explicit SubsetParameterization(int size,
const vector<int>& constant_parameters);
Expand All @@ -172,7 +172,7 @@ class SubsetParameterization : public LocalParameterization {
// with * being the quaternion multiplication operator. Here we assume
// that the first element of the quaternion vector is the real (cos
// theta) part.
class QuaternionParameterization : public LocalParameterization {
class CERES_EXPORT QuaternionParameterization : public LocalParameterization {
public:
virtual ~QuaternionParameterization() {}
virtual bool Plus(const double* x,
Expand Down
18 changes: 9 additions & 9 deletions include/ceres/loss_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@

namespace ceres {

class LossFunction {
class CERES_EXPORT LossFunction {
public:
virtual ~LossFunction() {}

Expand Down Expand Up @@ -128,7 +128,7 @@ class LossFunction {
// It is not normally necessary to use this, as passing NULL for the
// loss function when building the problem accomplishes the same
// thing.
class TrivialLoss : public LossFunction {
class CERES_EXPORT TrivialLoss : public LossFunction {
public:
virtual void Evaluate(double, double*) const;
};
Expand Down Expand Up @@ -171,7 +171,7 @@ class TrivialLoss : public LossFunction {
//
// The scaling parameter 'a' corresponds to 'delta' on this page:
// http://en.wikipedia.org/wiki/Huber_Loss_Function
class HuberLoss : public LossFunction {
class CERES_EXPORT HuberLoss : public LossFunction {
public:
explicit HuberLoss(double a) : a_(a), b_(a * a) { }
virtual void Evaluate(double, double*) const;
Expand All @@ -187,7 +187,7 @@ class HuberLoss : public LossFunction {
// rho(s) = 2 (sqrt(1 + s) - 1).
//
// At s = 0: rho = [0, 1, -1/2].
class SoftLOneLoss : public LossFunction {
class CERES_EXPORT SoftLOneLoss : public LossFunction {
public:
explicit SoftLOneLoss(double a) : b_(a * a), c_(1 / b_) { }
virtual void Evaluate(double, double*) const;
Expand All @@ -204,7 +204,7 @@ class SoftLOneLoss : public LossFunction {
// rho(s) = log(1 + s).
//
// At s = 0: rho = [0, 1, -1].
class CauchyLoss : public LossFunction {
class CERES_EXPORT CauchyLoss : public LossFunction {
public:
explicit CauchyLoss(double a) : b_(a * a), c_(1 / b_) { }
virtual void Evaluate(double, double*) const;
Expand All @@ -225,7 +225,7 @@ class CauchyLoss : public LossFunction {
// rho(s) = a atan(s / a).
//
// At s = 0: rho = [0, 1, 0].
class ArctanLoss : public LossFunction {
class CERES_EXPORT ArctanLoss : public LossFunction {
public:
explicit ArctanLoss(double a) : a_(a), b_(1 / (a * a)) { }
virtual void Evaluate(double, double*) const;
Expand Down Expand Up @@ -264,7 +264,7 @@ class ArctanLoss : public LossFunction {
// concentrated in the range a - b to a + b.
//
// At s = 0: rho = [0, ~0, ~0].
class TolerantLoss : public LossFunction {
class CERES_EXPORT TolerantLoss : public LossFunction {
public:
explicit TolerantLoss(double a, double b);
virtual void Evaluate(double, double*) const;
Expand Down Expand Up @@ -305,7 +305,7 @@ class ComposedLoss : public LossFunction {
// function, rho = NULL is a valid input and will result in the input
// being scaled by a. This provides a simple way of implementing a
// scaled ResidualBlock.
class ScaledLoss : public LossFunction {
class CERES_EXPORT ScaledLoss : public LossFunction {
public:
// Constructs a ScaledLoss wrapping another loss function. Takes
// ownership of the wrapped loss function or not depending on the
Expand Down Expand Up @@ -362,7 +362,7 @@ class ScaledLoss : public LossFunction {
//
// Solve(options, &problem, &summary)
//
class LossFunctionWrapper : public LossFunction {
class CERES_EXPORT LossFunctionWrapper : public LossFunction {
public:
LossFunctionWrapper(LossFunction* rho, Ownership ownership)
: rho_(rho), ownership_(ownership) {
Expand Down
2 changes: 1 addition & 1 deletion include/ceres/normal_prior.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ namespace ceres {
// which would be the case if the covariance matrix S is rank
// deficient.

class NormalPrior: public CostFunction {
class CERES_EXPORT NormalPrior: public CostFunction {
public:
// Check that the number of rows in the vector b are the same as the
// number of columns in the matrix A, crash otherwise.
Expand Down
4 changes: 2 additions & 2 deletions include/ceres/problem.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,9 +117,9 @@ typedef internal::ResidualBlock* ResidualBlockId;
// problem.AddResidualBlock(new MyBinaryCostFunction(...), x2, x3);
//
// Please see cost_function.h for details of the CostFunction object.
class Problem {
class CERES_EXPORT Problem {
public:
struct Options {
struct CERES_EXPORT Options {
Options()
: cost_function_ownership(TAKE_OWNERSHIP),
loss_function_ownership(TAKE_OWNERSHIP),
Expand Down
8 changes: 4 additions & 4 deletions include/ceres/solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace ceres {
class Problem;

// Interface for non-linear least squares solvers.
class Solver {
class CERES_EXPORT Solver {
public:
virtual ~Solver();

Expand All @@ -55,7 +55,7 @@ class Solver {
// problems; however, better performance is often obtainable with tweaking.
//
// The constants are defined inside types.h
struct Options {
struct CERES_EXPORT Options {
// Default constructor that sets up a generic sparse problem.
Options() {
minimizer_type = TRUST_REGION;
Expand Down Expand Up @@ -713,7 +713,7 @@ class Solver {
string solver_log;
};

struct Summary {
struct CERES_EXPORT Summary {
Summary();

// A brief one line description of the state of the solver after
Expand Down Expand Up @@ -951,7 +951,7 @@ class Solver {
};

// Helper function which avoids going through the interface.
void Solve(const Solver::Options& options,
CERES_EXPORT void Solve(const Solver::Options& options,
Problem* problem,
Solver::Summary* summary);

Expand Down
Loading

0 comments on commit 5d7eed8

Please sign in to comment.