#include <kdl_parser/kdl_parser.hpp>#include <ros/ros.h>#include <ros/package.h>#include <stdlib.h>#include <cmath>#include <kdl/frames.hpp>#include <kdl/chainfksolverpos_recursive.hpp>#include <kdl/chainidsolver_recursive_newton_euler.hpp>#include <kdl/chainiksolvervel_pinv.hpp>#include <sensor_msgs/JointState.h>
Go to the source code of this file.
Functions | |
| void | feel_efforts (ros::Publisher tau_pub) |
| void | js_cb (const sensor_msgs::JointState::ConstPtr &msg) |
| int | main (int argc, char **argv) |
Variables | |
| double | alpha = 0.5 |
| KDL::Chain | chain |
| bool | first_run = true |
| KDL::ChainIdSolver_RNE * | gcSolver |
| KDL::JntArray | jnt_q (mNumJnts) |
| KDL::JntArray | jnt_qd (mNumJnts) |
| KDL::JntArray | jnt_qdd (mNumJnts) |
| KDL::JntArray | jnt_taugc (mNumJnts) |
| sensor_msgs::JointState | joint_states |
| unsigned int | mNumJnts = 6 |
| sensor_msgs::JointState | model_states |
| KDL::Tree | my_tree |
| void feel_efforts | ( | ros::Publisher | tau_pub | ) |
Definition at line 82 of file svenzva_dynamics.cpp.
| void js_cb | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) |
Definition at line 71 of file svenzva_dynamics.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 137 of file svenzva_dynamics.cpp.
| double alpha = 0.5 |
Definition at line 69 of file svenzva_dynamics.cpp.
| KDL::Chain chain |
Definition at line 58 of file svenzva_dynamics.cpp.
| bool first_run = true |
Definition at line 66 of file svenzva_dynamics.cpp.
| KDL::ChainIdSolver_RNE* gcSolver |
Definition at line 67 of file svenzva_dynamics.cpp.
| KDL::JntArray jnt_q(mNumJnts) |
| KDL::JntArray jnt_qd(mNumJnts) |
| KDL::JntArray jnt_qdd(mNumJnts) |
| KDL::JntArray jnt_taugc(mNumJnts) |
| sensor_msgs::JointState joint_states |
Definition at line 56 of file svenzva_dynamics.cpp.
| unsigned int mNumJnts = 6 |
Definition at line 59 of file svenzva_dynamics.cpp.
| sensor_msgs::JointState model_states |
Definition at line 65 of file svenzva_dynamics.cpp.
| KDL::Tree my_tree |
Definition at line 57 of file svenzva_dynamics.cpp.