Cartesian Robot used for test purposes. This is a simple robot with simple kinematics. Each joint corresponds to a cartesian direction (i.e. x, y, R, P, Y) (don't ask me how this is built, it just works). More...
#include <cartesian_robot.h>

| Public Member Functions | |
| CartesianRobot () | |
| CartesianRobot (double pos_range, double orient_range, const std::vector< double > &joint_velocities=std::vector< double >(6, 1.0)) | |
| virtual bool | getAllIK (const Eigen::Affine3d &pose, std::vector< std::vector< double > > &joint_poses) const | 
| virtual int | getDOF () const | 
| virtual bool | getFK (const std::vector< double > &joint_pose, Eigen::Affine3d &pose) const | 
| virtual bool | getIK (const Eigen::Affine3d &pose, const std::vector< double > &seed_state, std::vector< double > &joint_pose) const | 
| virtual bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &world_frame, const std::string &tcp_frame) | 
| virtual bool | isValid (const std::vector< double > &joint_pose) const | 
| virtual bool | isValid (const Eigen::Affine3d &pose) const | 
| virtual bool | isValidMove (const std::vector< double > &from_joint_pose, const std::vector< double > &to_joint_pose, double dt) const | 
| bool | setJointVelocities (const std::vector< double > &new_joint_vels) | 
| Public Attributes | |
| std::vector< double > | joint_velocities_ | 
| double | orient_range_ | 
| double | pos_range_ | 
Cartesian Robot used for test purposes. This is a simple robot with simple kinematics. Each joint corresponds to a cartesian direction (i.e. x, y, R, P, Y) (don't ask me how this is built, it just works).
Definition at line 30 of file cartesian_robot.h.
Definition at line 38 of file cartesian_robot.cpp.
| descartes_trajectory_test::CartesianRobot::CartesianRobot | ( | double | pos_range, | 
| double | orient_range, | ||
| const std::vector< double > & | joint_velocities = std::vector<double>(6, 1.0) | ||
| ) | 
Definition at line 43 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::getAllIK | ( | const Eigen::Affine3d & | pose, | 
| std::vector< std::vector< double > > & | joint_poses | ||
| ) | const  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 80 of file cartesian_robot.cpp.
| int descartes_trajectory_test::CartesianRobot::getDOF | ( | ) | const  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 108 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::getFK | ( | const std::vector< double > & | joint_pose, | 
| Eigen::Affine3d & | pose | ||
| ) | const  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 87 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::getIK | ( | const Eigen::Affine3d & | pose, | 
| const std::vector< double > & | seed_state, | ||
| std::vector< double > & | joint_pose | ||
| ) | const  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 56 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::initialize | ( | const std::string & | robot_description, | 
| const std::string & | group_name, | ||
| const std::string & | world_frame, | ||
| const std::string & | tcp_frame | ||
| ) |  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 50 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::isValid | ( | const std::vector< double > & | joint_pose | ) | const  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 113 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::isValid | ( | const Eigen::Affine3d & | pose | ) | const  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 134 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::isValidMove | ( | const std::vector< double > & | from_joint_pose, | 
| const std::vector< double > & | to_joint_pose, | ||
| double | dt | ||
| ) | const  [virtual] | 
Implements descartes_core::RobotModel.
Definition at line 152 of file cartesian_robot.cpp.
| bool descartes_trajectory_test::CartesianRobot::setJointVelocities | ( | const std::vector< double > & | new_joint_vels | ) |  [inline] | 
Definition at line 57 of file cartesian_robot.h.
| std::vector<double> descartes_trajectory_test::CartesianRobot::joint_velocities_ | 
Definition at line 67 of file cartesian_robot.h.
Definition at line 66 of file cartesian_robot.h.
Definition at line 65 of file cartesian_robot.h.