Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: warn when solver fails. #241

Merged
merged 2 commits into from
Sep 19, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions HISTORY.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
### Changed

- [cpp]: fix numerical issue in Seidel solver for 1D problems. (#232)
- [cpp]: warn when solver fails. (#241)

## 0.6.0 (Mar 08 2023)

Expand Down
2 changes: 1 addition & 1 deletion cpp/src/toppra/algorithm/toppra.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ ReturnCode TOPPRA::computeForwardPass(value_type vel_start) {
solver_ret = m_solver->solveStagewiseOptim(i, H, g_upper, x, x_next, solution);
if (!solver_ret) {
ret = ReturnCode::ERR_FAIL_FORWARD_PASS;
TOPPRA_LOG_DEBUG("Fail: forward pass, idx: " << i);
TOPPRA_LOG_WARN("Fail: forward pass, idx: " << i);
break;
}
/// \todo This can be optimized further by solving a 1D problem instead of 2D
Expand Down
16 changes: 10 additions & 6 deletions cpp/src/toppra/geometric_path/piecewise_poly_path.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,15 @@
#include <toppra/geometric_path/piecewise_poly_path.hpp>

#include <iostream>
#include <iomanip>
#include <ostream>
#include <stdexcept>
#include <string>
#include <toppra/geometric_path/piecewise_poly_path.hpp>
#include <toppra/toppra.hpp>
#include <Eigen/Dense>
#include <array>

#include <Eigen/Dense>
#include <toppra/toppra.hpp>

#ifdef TOPPRA_OPT_MSGPACK
#include <msgpack.hpp>
#endif
Expand Down Expand Up @@ -238,10 +241,11 @@ Vectors PiecewisePolyPath::eval(const Vector &positions, int order) const {
}

size_t PiecewisePolyPath::findSegmentIndex(value_type pos) const {
if (pos > m_breakpoints[m_breakpoints.size()-1] || pos < m_breakpoints[0]) {
if (pos > m_breakpoints.back() || pos < m_breakpoints[0]) {
constexpr auto max_precision {std::numeric_limits<value_type>::digits10 + 1};
std::ostringstream oss;
oss << "Position " << pos << " is outside of range [ " << m_breakpoints[0]
<< ", " << m_breakpoints[m_breakpoints.size()-1] << ']';
oss << std::setprecision(max_precision) << "Position " << pos <<
" is outside of range [ " << m_breakpoints[0] << ", " << m_breakpoints.back() << ']';
throw std::runtime_error(oss.str());
}
auto it = std::upper_bound(m_breakpoints.begin(), m_breakpoints.end(), pos);
Expand Down
8 changes: 7 additions & 1 deletion cpp/src/toppra/solver/seidel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -342,7 +342,13 @@ bool Seidel::solveStagewiseOptim(std::size_t i,
active_c[k] = m_index_map[lpsol.active_c[k]];
return true;
}
TOPPRA_LOG_DEBUG("Seidel: solver fails (upper ? " << upper << ')');
TOPPRA_LOG_WARN("Seidel: solver fails"
"\ni = " << i <<
"\ng = " << g.transpose() <<
"\nx = " << x.transpose() <<
"\nxNext = " << xNext.transpose() <<
"\n"
);
return false;
}

Expand Down
Loading