motion.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2016 SoftBank Robotics Europe
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef MOTION_HPP
19 #define MOTION_HPP
20 
21 // NAOqi Headers
22 #include <qi/session.hpp>
23 
27 class Motion
28 {
29 public:
30  Motion(const qi::SessionPtr& session);
31 
33  void init(const std::vector <std::string> &joints_names);
34 
36  bool robotIsWakeUp();
37 
39  void wakeUp();
40 
42  void rest();
43 
45  std::vector <std::string> getBodyNames(const std::string &robot_part);
46 
48  std::vector <std::string> getBodyNamesFromGroup(const std::vector<std::string> &motor_groups);
49 
51  void manageConcurrence();
52 
54  void moveTo(const float& vel_x, const float& vel_y, const float& vel_th);
55 
57  std::vector<double> getAngles(const std::string &robot_part);
58 
60  void writeJoints(const std::vector <double> &joint_commands);
61 
63  bool stiffnessInterpolation(const std::string &motor_group,
64  const float &stiffness,
65  const float &time);
66 
68  bool stiffnessInterpolation(const std::vector<std::string> &motor_groups,
69  const float &stiffness,
70  const float &time);
71 
73  bool setStiffnessArms(const float &stiffness, const float &time);
74 
75 private:
77  qi::AnyObject motion_proxy_;
78 
80  std::vector <std::string> joints_names_;
81 };
82 
83 #endif // MOTION_HPP
bool setStiffnessArms(const float &stiffness, const float &time)
set stiffness for arms
Definition: motion.cpp:248
void moveTo(const float &vel_x, const float &vel_y, const float &vel_th)
Move the robot at given velocity and angle.
Definition: motion.cpp:170
void manageConcurrence()
Manage concurrence of DCM and ALMotion.
Definition: motion.cpp:147
void wakeUp()
wake up the robot
Definition: motion.cpp:86
std::vector< std::string > getBodyNamesFromGroup(const std::vector< std::string > &motor_groups)
get body names based on motor groups
Definition: motion.cpp:135
This class is a wapper for Naoqi Motion Class.
Definition: motion.hpp:27
qi::AnyObject motion_proxy_
Definition: motion.hpp:77
std::vector< double > getAngles(const std::string &robot_part)
get joints angles
Definition: motion.cpp:184
void init(const std::vector< std::string > &joints_names)
initialize with joints names to control
Definition: motion.cpp:66
Motion(const qi::SessionPtr &session)
Definition: motion.cpp:24
std::vector< std::string > joints_names_
Definition: motion.hpp:80
void writeJoints(const std::vector< double > &joint_commands)
set joints values
Definition: motion.cpp:200
void rest()
go to the rest position
Definition: motion.cpp:103
bool robotIsWakeUp()
check if the robot is waked up
Definition: motion.cpp:71
std::vector< std::string > getBodyNames(const std::string &robot_part)
get body names
Definition: motion.cpp:120
bool stiffnessInterpolation(const std::string &motor_group, const float &stiffness, const float &time)
set stiffness for one motor group
Definition: motion.cpp:229


naoqi_dcm_driver
Author(s): Konstantinos Chatzilygeroudis , Mikael Arguedas , Karsten Knese , Natalia Lyubova
autogenerated on Thu Jul 25 2019 03:49:27