00001 /****************************************************************************** 00002 * Copyright (c) 2011 00003 * Locomotec 00004 * 00005 * Author: 00006 * Sebastian Blumenthal 00007 * 00008 * 00009 * This software is published under a dual-license: GNU Lesser General Public 00010 * License LGPL 2.1 and BSD license. The dual-license implies that users of this 00011 * code may choose which terms they prefer. 00012 * 00013 * Redistribution and use in source and binary forms, with or without 00014 * modification, are permitted provided that the following conditions are met: 00015 * 00016 * * Redistributions of source code must retain the above copyright 00017 * notice, this list of conditions and the following disclaimer. 00018 * * Redistributions in binary form must reproduce the above copyright 00019 * notice, this list of conditions and the following disclaimer in the 00020 * documentation and/or other materials provided with the distribution. 00021 * * Neither the name of Locomotec nor the names of its 00022 * contributors may be used to endorse or promote products derived from 00023 * this software without specific prior written permission. 00024 * 00025 * This program is free software: you can redistribute it and/or modify 00026 * it under the terms of the GNU Lesser General Public License LGPL as 00027 * published by the Free Software Foundation, either version 2.1 of the 00028 * License, or (at your option) any later version or the BSD license. 00029 * 00030 * This program is distributed in the hope that it will be useful, 00031 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00032 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00033 * GNU Lesser General Public License LGPL and the BSD license for more details. 00034 * 00035 * You should have received a copy of the GNU Lesser General Public 00036 * License LGPL and BSD license along with this program. 00037 * 00038 ******************************************************************************/ 00039 00040 #ifndef YOUBOTCONFIGURATION_H_ 00041 #define YOUBOTCONFIGURATION_H_ 00042 00043 /* ROS includes */ 00044 #include <ros/ros.h> 00045 #include <tf/transform_broadcaster.h> 00046 00047 /* OODL includes */ 00048 #include <youbot_driver/youbot/YouBotBase.hpp> 00049 #include <youbot_driver/youbot/YouBotManipulator.hpp> 00050 #include <actionlib/server/simple_action_server.h> 00051 #include <control_msgs/FollowJointTrajectoryAction.h> 00052 00053 typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> Server; 00054 00055 class JointTrajectoryAction; 00056 00057 namespace youBot 00058 { 00059 00060 class YouBotBaseConfiguration 00061 { 00062 public: 00063 00065 YouBotBaseConfiguration(); 00066 00068 virtual ~YouBotBaseConfiguration(); 00069 00071 youbot::YouBotBase* youBotBase; 00072 00074 std::string baseID; 00075 00077 std::vector<std::string> wheelNames; 00078 00080 ros::Subscriber baseCommandSubscriber; 00081 00083 ros::Publisher baseOdometryPublisher; 00084 00086 ros::Publisher baseJointStatePublisher; 00087 00089 ros::ServiceServer switchOffMotorsService; 00090 00092 ros::ServiceServer switchONMotorsService; 00093 00095 tf::TransformBroadcaster odometryBroadcaster; 00096 00097 }; 00098 00099 class YouBotArmConfiguration 00100 { 00101 public: 00102 00104 YouBotArmConfiguration(); 00105 00107 virtual ~YouBotArmConfiguration(); 00108 00110 youbot::YouBotManipulator* youBotArm; 00111 00113 std::string armID; 00114 00116 std::string commandTopicName; 00117 00119 std::string parentFrameIDName; 00120 00122 std::vector<std::string> jointNames; 00123 00125 std::vector<std::string> gripperFingerNames; 00126 00127 const static unsigned int LEFT_FINGER_INDEX = 0; 00128 const static unsigned int RIGHT_FINGER_INDEX = 1; 00129 00131 ros::Subscriber armPositionCommandSubscriber; 00132 00134 ros::Subscriber armVelocityCommandSubscriber; 00135 00137 actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> *armJointTrajectoryAction; 00138 00140 ros::Subscriber gripperPositionCommandSubscriber; 00141 00143 ros::Publisher armJointStatePublisher; 00144 00146 ros::ServiceServer switchOffMotorsService; 00147 00149 ros::ServiceServer switchONMotorsService; 00150 00152 ros::ServiceServer calibrateService; 00153 00154 //Server* trajectoryActionServer; 00155 //JointTrajectoryAction* jointTrajectoryAction; 00156 00163 double lastGripperCommand; 00164 00165 }; 00166 00170 class YouBotConfiguration 00171 { 00172 public: 00173 YouBotConfiguration(); 00174 virtual ~YouBotConfiguration(); 00175 00177 std::string configurationFilePath; 00178 00180 bool hasBase; 00181 00183 bool hasArms; 00184 00186 YouBotBaseConfiguration baseConfiguration; 00187 00189 std::vector<YouBotArmConfiguration> youBotArmConfigurations; 00190 std::map<std::string, int> armNameToArmIndexMapping; 00191 00193 ros::Publisher diagnosticArrayPublisher; 00194 00195 ros::Publisher dashboardMessagePublisher; 00196 }; 00197 00198 } // namespace youBot 00199 00200 #endif /* YOUBOTCONFIGURATION_H_ */ 00201 00202 /* EOF */