1#ifndef WBC_PY_VELOCITY_SCENE_QP_HPP 
    2#define WBC_PY_VELOCITY_SCENE_QP_HPP 
    4#include <wbc/scenes/velocity_qp/VelocitySceneQP.hpp> 
   10wbc::JointWeights 
toJointWeights(
const base::NamedVector<double> &weights);
 
   14    VelocitySceneQP(std::shared_ptr<RobotModelRBDL> robot_model, std::shared_ptr<QPOASESSolver> solver, 
const double dt);
 
   15    void setJointReference(
const std::string& task_name, 
const base::NamedVector<base::JointState>& ref);
 
   16    void setCartReference(
const std::string& task_name, 
const base::samples::RigidBodyStateSE3& ref);
 
   20    base::NamedVector<base::JointState> 
solve2(
const wbc::HierarchicalQP &hqp);
 
 
Definition velocity_scene_qp.hpp:12
 
base::NamedVector< double > getJointWeights2()
Definition velocity_scene_qp.cpp:48
 
base::NamedVector< wbc::TaskStatus > updateTasksStatus2()
Definition velocity_scene_qp.cpp:57
 
void setJointReference(const std::string &task_name, const base::NamedVector< base::JointState > &ref)
Definition velocity_scene_qp.cpp:39
 
VelocitySceneQP(std::shared_ptr< RobotModelRBDL > robot_model, std::shared_ptr< QPOASESSolver > solver, const double dt)
Definition velocity_scene_qp.cpp:36
 
base::NamedVector< double > getActuatedJointWeights2()
Definition velocity_scene_qp.cpp:51
 
base::NamedVector< base::JointState > solve2(const wbc::HierarchicalQP &hqp)
Definition velocity_scene_qp.cpp:54
 
void setJointWeights(const base::NamedVector< double > &weights)
Definition velocity_scene_qp.cpp:45
 
void setCartReference(const std::string &task_name, const base::samples::RigidBodyStateSE3 &ref)
Definition velocity_scene_qp.cpp:42
 
Definition base_types_conversion.h:14
 
wbc::JointWeights toJointWeights(const base::NamedVector< double > &weights)
Definition acceleration_scene.cpp:8