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

Err when execute './DiscretePointsSmoother' #2

Open
zhthree3 opened this issue Sep 25, 2023 · 6 comments
Open

Err when execute './DiscretePointsSmoother' #2

zhthree3 opened this issue Sep 25, 2023 · 6 comments

Comments

@zhthree3
Copy link

When I execute './DiscretePointsSmoother', thrhe following error occurred:

*** The problem solved in 20 iterations!
loop iteration number is 36
iterative anchoring path smoother time: 3432.76 ms.
total_t is : 220.685
ERROR in validate_data: P is not upper triangular
ERROR in osqp_setup: Problem data validation.
ERROR in osqp_solve: Solver workspace not initialized.
segment fault(core dumped)

@FasonLee
Copy link
Owner

This is caused by the version of osqp. Versions of osqp-0.6 and above require P to be an upper triangle. You can roll back the osqp version. In this project I am using v0.4.1

git clone https://github.com/osqp/osqp.git
cd osqp
git checkout v0.4.1   ## This step is necessary!
mkdir build && cd build  
cmake ..  
make  
sudo make install  

@zhthree3
Copy link
Author

Thanks!I have rolled back the osqp version to v0.4.1 and the problem was solved. Do you have any plans to make it adapt to a higher version of osqp?

@FasonLee
Copy link
Owner

It is recommended that in the autoware code, there is an interface class that converts the eigen matrix into csc_matrix format. I haven't used it, but you can try it:
https://github.com/tier4/AutowareArchitectureProposal.iv/tree/use-autoware-auto-msgs/common/math/osqp_interface/include/osqp_interface

@zhthree3
Copy link
Author

Thanks for the advice, I'll try it.

@TYB2
Copy link

TYB2 commented Oct 18, 2023

I have tried it. if we use ospq v0.6.0, here has two tips:

  1. The matrix needs to be symmetric and only provide the upper triangular part of the matrix
  columns[2 * n + i].emplace_back(2 * n + i + 1,
                              -2.0 * weight_dddx_ / delta_s_square /
                             (scale_factor_[2] * scale_factor_[2]));

change to

    columns[2 * n + i + 1].emplace_back(2 * n + i,
                                    -1.0 * weight_dddx_ / delta_s_square /
                                        (scale_factor_[2] * scale_factor_[2]));
  1. The row number in each column needs to be incremented.

final code:

void PiecewiseJerkSpeedProblem::CalculateKernel(std::vector<c_float>* P_data,
                                                std::vector<c_int>* P_indices,
                                                std::vector<c_int>* P_indptr) {
  const int n = static_cast<int>(num_of_knots_);
  const int kNumParam = 3 * n;
  const int kNumValue = 4 * n - 1;
  std::vector<std::vector<std::pair<c_int, c_float>>> columns;
  columns.resize(kNumParam);
  int value_index = 0;

  // x(i)^2 * w_x_ref
  for (int i = 0; i < n - 1; ++i) {
    columns[i].emplace_back(
        i, weight_x_ref_ / (scale_factor_[0] * scale_factor_[0]));
    ++value_index;
  }
  // x(n-1)^2 * (w_x_ref + w_end_x)
  columns[n - 1].emplace_back(n - 1, (weight_x_ref_ + weight_end_state_[0]) /
                                         (scale_factor_[0] * scale_factor_[0])); 
  ++value_index;

  // x(i)'^2 * (w_dx_ref + penalty_dx) penalty_dx
  for (int i = 0; i < n - 1; ++i) {
    columns[n + i].emplace_back(n + i,
                                (weight_dx_ref_ + penalty_dx_[i]) /
                                    (scale_factor_[1] * scale_factor_[1]));
    ++value_index;
  }

  // x(n-1)'^2 * (w_dx_ref + penalty_dx + w_end_dx)
  columns[2 * n - 1].emplace_back(
      2 * n - 1, (weight_dx_ref_ + penalty_dx_[n - 1] + weight_end_state_[1]) /
                     (scale_factor_[1] * scale_factor_[1]));
  ++value_index;

  auto delta_s_square = delta_s_ * delta_s_;
  // -2 * w_dddx / delta_s^2 * x(i)'' * x(i + 1)''
  for (int i = 0; i < n - 1; ++i) {
    // columns[2 * n + i].emplace_back(2 * n + i + 1,
    //                                 -2.0 * weight_dddx_ / delta_s_square /
    //                                     (scale_factor_[2] * scale_factor_[2]));
    columns[2 * n + i + 1].emplace_back(2 * n + i,
                                    -1.0 * weight_dddx_ / delta_s_square /
                                        (scale_factor_[2] * scale_factor_[2]));
    ++value_index;
  } 

  // x(i)''^2 * (w_ddx + 2 * w_dddx / delta_s^2)
  columns[2 * n].emplace_back(2 * n,
                              (weight_ddx_ + weight_dddx_ / delta_s_square) /
                                  (scale_factor_[2] * scale_factor_[2]));
  ++value_index;

  for (int i = 1; i < n - 1; ++i) {
    columns[2 * n + i].emplace_back(
        2 * n + i, (weight_ddx_ + 2.0 * weight_dddx_ / delta_s_square) /
                       (scale_factor_[2] * scale_factor_[2]));
    ++value_index;
  }

  columns[3 * n - 1].emplace_back(
      3 * n - 1,
      (weight_ddx_ + weight_dddx_ / delta_s_square + weight_end_state_[2]) /
          (scale_factor_[2] * scale_factor_[2]));
  ++value_index;

  // CHECK_EQ(value_index, kNumValue);

  int ind_p = 0;
  for (int i = 0; i < kNumParam; ++i) {
    P_indptr->push_back(ind_p);
    for (const auto& row_data_pair : columns[i]) {
      P_data->push_back(row_data_pair.second * 2.0);
      P_indices->push_back(row_data_pair.first);
      ++ind_p;
    }
  }
  P_indptr->push_back(ind_p);
}

@yufeifeiyu
Copy link

请问ADOLC库怎么安装

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants