33 action_client(
"katana_arm_controller/joint_movement_action", true), gripper_(
"gripper_grasp_posture_controller", true)
35 ROS_INFO(
"KatanaTeleopKey starting...");
56 if (!n_.
getParam(
"katana_joints", joint_names))
67 for (
size_t i = 0; (int)i < joint_names.
size(); ++i)
73 ROS_ERROR(
"Array of joint names should contain all strings. (namespace: %s)",
84 if (!n_.
getParam(
"katana_gripper_joints", gripper_joint_names))
95 for (
size_t i = 0; (int)i < gripper_joint_names.
size(); ++i)
100 ROS_ERROR(
"Array of gripper joint names should contain all strings. (namespace: %s)",
125 ROS_INFO(
"---------------------------");
126 ROS_INFO(
"Use 'WS' to increase/decrease the joint position about one increment");
129 ROS_INFO(
"Use ',.' to alter the increment_step_size altering the scaling factor by -/+ 1.0");
131 ROS_INFO(
"---------------------------");
132 ROS_INFO(
"Use 'R' to return to the arm's initial pose");
133 ROS_INFO(
"Use 'I' to display this manual and the current joint state");
134 ROS_INFO(
"---------------------------");
135 ROS_INFO(
"Use 'AD' to switch to the next/previous joint");
136 ROS_INFO(
"Use '0-9' to select a joint by number");
137 ROS_INFO(
"---------------------------");
138 ROS_INFO(
"Use 'OC' to open/close gripper");
152 ROS_INFO(
"---------------------------");
153 ROS_INFO(
"Current Joint Positions:");
155 for (
unsigned int i = 0; i <
current_pose_.position.size(); i++)
180 bool found_match =
false;
205 tcgetattr(
kfd, &cooked);
206 memcpy(&
raw, &cooked,
sizeof(
struct termios));
207 raw.c_lflag &= ~(ICANON | ECHO);
211 tcsetattr(
kfd, TCSANOW, &
raw);
226 if (read(
kfd, &c, 1) < 0)
232 size_t selected_joint_index;
281 ROS_INFO(
"Resetting arm to its initial pose..");
292 ROS_INFO(
"Shutting down the Katana Teleoperation node...");
359 ROS_INFO(
"Sending new JointMovementActionGoal..");
361 katana_msgs::JointMovementGoal goal;
364 for (
size_t i = 0; i < goal.jointGoal.name.size(); i++)
366 ROS_DEBUG(
"Joint: %s to %f rad", goal.jointGoal.name[i].c_str(), goal.jointGoal.position[i]);
371 if (!finished_within_time)
374 ROS_INFO(
"Timed out achieving goal!");
400 goal.command.position = -0.44;
405 goal.command.position = 0.3;
410 ROS_ERROR(
"unknown goal code (%d)", goal_type);
416 bool finished_within_time =
false;
419 if (!finished_within_time)
422 ROS_WARN(
"Timed out achieving goal!");
442 tcsetattr(
kfd, TCSANOW, &cooked);
446 int main(
int argc,
char** argv)
448 ros::init(argc, argv,
"katana_teleop_key");
452 signal(SIGINT,
quit);
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Type const & getType() const
bool send_gripper_action(int32_t goal_type)
std::string toString() const
std::vector< std::string > gripper_joint_names_
void jointStateCallback(const sensor_msgs::JointState::ConstPtr &js)
sensor_msgs::JointState current_pose_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string & getNamespace() const
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
ROSCONSOLE_DECL void shutdown()
control_msgs::GripperCommandGoal GCG
bool getParam(const std::string &key, std::string &s) const
sensor_msgs::JointState initial_pose_
std::vector< std::string > combined_joints_
sensor_msgs::JointState movement_goal_
SimpleClientGoalState getState() const
std::vector< std::string > joint_names_
actionlib::SimpleActionClient< control_msgs::GripperCommandAction > gripper_
struct termios cooked raw
ROSCPP_DECL void spinOnce()
double increment_step_scaling
bool matchJointGoalRequest(double increment)