#include <acceleration_scene.hpp>
◆ AccelerationScene()
wbc_py::AccelerationScene::AccelerationScene |
( |
std::shared_ptr< RobotModelRBDL > | robot_model, |
|
|
std::shared_ptr< QPOASESSolver > | solver, |
|
|
const double | dt ) |
◆ getActuatedJointWeights2()
base::NamedVector< double > wbc_py::AccelerationScene::getActuatedJointWeights2 |
( |
| ) |
|
◆ getJointWeights2()
base::NamedVector< double > wbc_py::AccelerationScene::getJointWeights2 |
( |
| ) |
|
◆ setCartReference()
void wbc_py::AccelerationScene::setCartReference |
( |
const std::string & | task_name, |
|
|
const base::samples::RigidBodyStateSE3 & | ref ) |
◆ setJointReference()
void wbc_py::AccelerationScene::setJointReference |
( |
const std::string & | task_name, |
|
|
const base::NamedVector< base::JointState > & | ref ) |
◆ setJointWeights()
void wbc_py::AccelerationScene::setJointWeights |
( |
const base::NamedVector< double > & | weights | ) |
|
◆ solve2()
base::NamedVector< base::JointState > wbc_py::AccelerationScene::solve2 |
( |
const wbc::HierarchicalQP & | hqp | ) |
|
◆ updateTasksStatus2()
base::NamedVector< wbc::TaskStatus > wbc_py::AccelerationScene::updateTasksStatus2 |
( |
| ) |
|
The documentation for this class was generated from the following files: