1#ifndef WBC_PY_VELOCITY_SCENE_HPP
2#define WBC_PY_VELOCITY_SCENE_HPP
4#include <wbc/scenes/velocity/VelocityScene.hpp>
10wbc::JointWeights
toJointWeights(
const base::NamedVector<double> &weights);
14 VelocityScene(std::shared_ptr<RobotModelRBDL> robot_model, std::shared_ptr<HierarchicalLSSolver> 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.hpp:12
base::NamedVector< double > getJointWeights2()
Definition velocity_scene.cpp:48
void setJointWeights(const base::NamedVector< double > &weights)
Definition velocity_scene.cpp:45
base::NamedVector< double > getActuatedJointWeights2()
Definition velocity_scene.cpp:51
void setJointReference(const std::string &task_name, const base::NamedVector< base::JointState > &ref)
Definition velocity_scene.cpp:39
base::NamedVector< base::JointState > solve2(const wbc::HierarchicalQP &hqp)
Definition velocity_scene.cpp:54
void setCartReference(const std::string &task_name, const base::samples::RigidBodyStateSE3 &ref)
Definition velocity_scene.cpp:42
base::NamedVector< wbc::TaskStatus > updateTasksStatus2()
Definition velocity_scene.cpp:57
VelocityScene(std::shared_ptr< RobotModelRBDL > robot_model, std::shared_ptr< HierarchicalLSSolver > solver, const double dt)
Definition velocity_scene.cpp:36
Definition base_types_conversion.h:14
wbc::JointWeights toJointWeights(const base::NamedVector< double > &weights)
Definition acceleration_scene.cpp:8