Skip to content

Commit

Permalink
merge
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake committed Nov 19, 2014
2 parents a6f11bc + 4d452c3 commit ef86054
Show file tree
Hide file tree
Showing 5 changed files with 336 additions and 23 deletions.
11 changes: 10 additions & 1 deletion solvers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,18 @@ if (gurobi_FOUND AND eigen3_FOUND)
pods_install_headers(fastQP.h gurobiQP.h DESTINATION drake)
pods_install_pkg_config_file(drake-qp
LIBS -ldrakeQP
REQUIRES gurobi
REQUIRES gurobi
VERSION 0.0.1)

endif()

pods_find_pkg_config(snopt_cpp)


if(snopt_cpp_FOUND)
find_library(GFORTRAN_LIBRARY NAMES gfortran libgfortran PATHS ${MATLAB_ROOT}/sys/os/*/)
add_mex(NonlinearProgramSnoptmex NonlinearProgramSnoptmex.cpp)
pods_use_pkg_config_packages(NonlinearProgramSnoptmex snopt_cpp)
set_target_properties(NonlinearProgramSnoptmex PROPERTIES COMPILE_FLAGS -fPIC)
target_link_libraries(NonlinearProgramSnoptmex ${GFORTRAN_LIBRARY})
endif()
55 changes: 34 additions & 21 deletions solvers/NonlinearProgram.m
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,8 @@

bbcon_lb % A obj.num_vars x length(obj.bbcon) matrix. bbcon_lb(:,i) is the lower bound of x coming from the BoundingBoxConstraint obj.bbcon{i}
bbcon_ub % A obj.num_vars x length(obj.bbcon) matrix. bbcon_lb(:,i) is the upper bound of x coming from the BoundingBoxConstraint obj.bbcon{i}
which_snopt % 1 if NonlinearProgramSnoptmex is used.
% 2 if user has their own snopt in MATLAB path
end

properties (Access = protected)
Expand Down Expand Up @@ -165,7 +167,7 @@
obj.solver_options.snopt.VerifyLevel = 0;
obj.solver_options.snopt.DerivativeOption = 1;
obj.solver_options.snopt.print = '';
obj.solver_options.snopt.scaleoption = 0;
obj.solver_options.snopt.ScaleOption = 0;
obj.solver_options.snopt.NewBasisFile = 0;
obj.solver_options.snopt.OldBasisFile = 0;
obj.solver_options.snopt.BackupBasisFile = 0;
Expand Down Expand Up @@ -707,10 +709,14 @@
% @param solver Can be 'snopt', 'ipopt', 'fmincon' and 'default'.
typecheck(solver,'char');
if(strcmp(solver,'snopt'))
if(~checkDependency('snopt'))
if(checkDependency('NonlinearProgramSnoptmex'))
obj.which_snopt = 1;
elseif(checkDependency('snopt'))
obj.which_snopt = 2;
else
error('Drake:NonlinearProgram:UnsupportedSolver',' SNOPT not found. SNOPT support will be disabled.');
end
obj.solver = solver;
obj.solver = 'snopt';
elseif(strcmp(solver,'studentSnopt'))
if(~checkDependency('studentSnopt'))
error('Drake:NonlinearProgram:UnsupportedSOlver',' SNOPT not found. SNOPT support will be disabled.');
Expand Down Expand Up @@ -805,12 +811,12 @@
obj.solver_options.snopt.print = optionval;
elseif(strcmpi(optionname(~isspace(optionname)),'scaleoption'))
if(~isnumeric(optionval) || numel(optionval) ~= 1)
error('Drake:NonlinearProgram:setSolverOptions:scaleoption should be a scalar');
error('Drake:NonlinearProgram:setSolverOptions:ScaleOption should be a scalar');
end
if(optionval ~= 0 && optionval ~= 1 && optionval ~= 2)
error('Drake:NonlinearProgram:setSolverOptions:scaleoption should be either 0,1 or 2');
error('Drake:NonlinearProgram:setSolverOptions:ScaleOption should be either 0,1 or 2');
end
obj.solver_options.snopt.scaleoption = optionval;
obj.solver_options.snopt.ScaleOption = optionval;
elseif(strcmpi(optionname(~isspace(optionname)),'oldbasisfile'))
if(~isnumeric(optionval) || numel(optionval) ~= 1)
error('Drake:NonlinearProgram:setSolverOptions:OptionVal', 'OldBasisFile should be a scalar');
Expand All @@ -828,7 +834,7 @@
obj.solver_options.snopt.BackupBasisFile = optionval;
elseif(strcmpi(optionname(~isspace(optionname)),'linesearchtolerance'))
if(~isnumeric(optionval) || numel(optionval) ~= 1)
error('Drake:NonlinearProgram:setSolverOptions:scaleoption should be a scalar');
error('Drake:NonlinearProgram:setSolverOptions:LineSearchTolerance should be a scalar');
end
if(optionval < 0 || optionval > 1)
error('Drake:NonlinearProgram:setSolverOptions:OptionVal', 'LinesearchTolerance should be between 0 and 1');
Expand All @@ -837,7 +843,7 @@
elseif(strcmpi(optionname(~isspace(optionname)),'sense'))
if(~ischar(optionval))
error('Drake:NonlinearProgram:setSolverOptions:OptionVal', 'sense should be a string');
end
end
if(~any(strcmp(optionval,{'Minimize','Maximize','Feasible point'})))
error('Drake:NonlinearProgram:setSolverOptions:Sense', ...
'sense must be one of the following: ''Minimize'', ''Maximize'', ''Feasible point''');
Expand Down Expand Up @@ -1279,7 +1285,7 @@
snseti('Backup Basis File',obj.solver_options.snopt.BackupBasisFile);
snsetr('Linesearch tolerance',obj.solver_options.snopt.LinesearchTolerance);
snset(obj.solver_options.snopt.sense)

function [f,G] = snopt_userfun(x_free)
x_all = zeros(obj.num_vars,1);
x_all(free_x_idx) = x_free;
Expand Down Expand Up @@ -1324,16 +1330,23 @@ function checkGradient(x_free)
checkGradient(x0_free);
end

if(~isempty(obj.solver_options.snopt.print))
snprint(obj.solver_options.snopt.print);
end
[x_free,objval,exitflag] = snopt(x0_free, ...
x_lb_free,x_ub_free, ...
lb,ub,...
'snoptUserfun',...
0,1,...
Avals,iAfun,jAvar,...
iGfun_free,jGvar_free);
if(obj.which_snopt == 1)
[x_free,objval,exitflag,xmul,Fmul] = NonlinearProgramSnoptmex(x0_free, ...
x_lb_free,x_ub_free, ...
lb,ub,...
'snoptUserfun',...
0,1,...
Avals,iAfun,jAvar,...
iGfun_free,jGvar_free,obj.solver_options.snopt);
elseif(obj.which_snopt == 2)
[x_free,objval,exitflag,xmul,Fmul] = snopt(x0_free, ...
x_lb_free,x_ub_free, ...
lb,ub,...
'snoptUserfun',...
0,1,...
Avals,iAfun,jAvar,...
iGfun_free,jGvar_free);
end
if(obj.check_grad)
display('check the gradient for the SNOPT solution');
checkGradient(x_free);
Expand Down Expand Up @@ -1367,7 +1380,7 @@ function checkGradient(x_free)
for i = 1:length(algorithms)
fmincon_options.Algorithm = algorithms{i};
try
[x,objval,exitflag] = fmincon(@obj.objective,x0,full(obj.Ain),...
[x,objval,exitflag] = fmincon(@obj.objective,x0,full(obj.Ain),...
obj.bin,full(obj.Aeq),obj.beq,obj.x_lb,obj.x_ub,@fmincon_userfun,fmincon_options);
catch err
if(~strcmp(err.identifier,'optimlib:fmincon:ConstrTRR'))
Expand All @@ -1380,7 +1393,7 @@ function checkGradient(x_free)
end
else
[x,objval,exitflag] = fmincon(@obj.objective,x0,full(obj.Ain),...
obj.bin,full(obj.Aeq),obj.beq,obj.x_lb,obj.x_ub,@fmincon_userfun,obj.solver_options.fmincon);
obj.bin,full(obj.Aeq),obj.beq,obj.x_lb,obj.x_ub,@fmincon_userfun,obj.solver_options.fmincon);
end
objval = full(objval);

Expand Down
Loading

0 comments on commit ef86054

Please sign in to comment.