Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #ifndef CARTESIAN_ROBOT_H_
00020 #define CARTESIAN_ROBOT_H_
00021
00022 #include "descartes_core/robot_model.h"
00023
00024 namespace descartes_trajectory_test
00025 {
00030 class CartesianRobot : public descartes_core::RobotModel
00031 {
00032 public:
00033 CartesianRobot();
00034
00035 CartesianRobot(double pos_range, double orient_range,
00036 const std::vector<double> &joint_velocities = std::vector<double>(6, 1.0));
00037
00038 virtual bool getIK(const Eigen::Affine3d &pose, const std::vector<double> &seed_state,
00039 std::vector<double> &joint_pose) const;
00040
00041 virtual bool getAllIK(const Eigen::Affine3d &pose, std::vector<std::vector<double> > &joint_poses) const;
00042
00043 virtual bool getFK(const std::vector<double> &joint_pose, Eigen::Affine3d &pose) const;
00044
00045 virtual bool isValid(const std::vector<double> &joint_pose) const;
00046
00047 virtual bool isValid(const Eigen::Affine3d &pose) const;
00048
00049 virtual int getDOF() const;
00050
00051 virtual bool initialize(const std::string &robot_description, const std::string &group_name,
00052 const std::string &world_frame, const std::string &tcp_frame);
00053
00054 virtual bool isValidMove(const std::vector<double> &from_joint_pose, const std::vector<double> &to_joint_pose,
00055 double dt) const;
00056
00057 bool setJointVelocities(const std::vector<double> &new_joint_vels)
00058 {
00059 if (new_joint_vels.size() != joint_velocities_.size())
00060 return false;
00061 joint_velocities_ = new_joint_vels;
00062 return true;
00063 }
00064
00065 double pos_range_;
00066 double orient_range_;
00067 std::vector<double> joint_velocities_;
00068 };
00069 }
00070
00071 #endif // CARTESIAN_ROBOT_H