22 #include <qi/session.hpp> 30 Motion(
const qi::SessionPtr& session);
33 void init(
const std::vector <std::string> &joints_names);
45 std::vector <std::string>
getBodyNames(
const std::string &robot_part);
54 void moveTo(
const float& vel_x,
const float& vel_y,
const float& vel_th);
57 std::vector<double>
getAngles(
const std::string &robot_part);
60 void writeJoints(
const std::vector <double> &joint_commands);
64 const float &stiffness,
69 const float &stiffness,
bool setStiffnessArms(const float &stiffness, const float &time)
set stiffness for arms
void moveTo(const float &vel_x, const float &vel_y, const float &vel_th)
Move the robot at given velocity and angle.
void manageConcurrence()
Manage concurrence of DCM and ALMotion.
void wakeUp()
wake up the robot
std::vector< std::string > getBodyNamesFromGroup(const std::vector< std::string > &motor_groups)
get body names based on motor groups
This class is a wapper for Naoqi Motion Class.
qi::AnyObject motion_proxy_
std::vector< double > getAngles(const std::string &robot_part)
get joints angles
void init(const std::vector< std::string > &joints_names)
initialize with joints names to control
Motion(const qi::SessionPtr &session)
std::vector< std::string > joints_names_
void writeJoints(const std::vector< double > &joint_commands)
set joints values
void rest()
go to the rest position
bool robotIsWakeUp()
check if the robot is waked up
std::vector< std::string > getBodyNames(const std::string &robot_part)
get body names
bool stiffnessInterpolation(const std::string &motor_group, const float &stiffness, const float &time)
set stiffness for one motor group