$search
00001 #include "ros/ros.h" 00002 #include "std_msgs/String.h" 00003 #include "sensor_msgs/JointState.h" 00004 #include "pr2_controllers_msgs/JointTrajectoryControllerState.h" 00005 #include "brics_actuator/JointVelocities.h" 00006 #include "cob_srvs/Trigger.h" 00007 #include "cob_srvs/SetOperationMode.h" 00008 // #include "ros_canopen/posmsg.h" 00009 #include <iostream> 00010 #include <map> 00011 #include <boost/bind.hpp> 00012 #include <boost/filesystem.hpp> 00013 #include <canopen.h> 00014 // #include "yaml-cpp/yaml.h" 00015 #include <XmlRpcValue.h> 00016 00017 typedef boost::function< 00018 bool(cob_srvs::Trigger::Request&, 00019 cob_srvs::Trigger::Response&)> TriggerType; 00020 typedef boost::function< 00021 void(const brics_actuator::JointVelocities&)> JointVelocitiesType; 00022 typedef boost::function< 00023 bool(cob_srvs::SetOperationMode::Request&, 00024 cob_srvs::SetOperationMode::Response&)> SetOperationModeCallbackType; 00025 00026 struct BusParams { 00027 std::string baudrate; 00028 uint32_t syncInterval; 00029 }; 00030 std::map<std::string, BusParams> buses; 00031 00032 std::string deviceFile; 00033 00034 bool CANopenInit(cob_srvs::Trigger::Request &req, 00035 cob_srvs::Trigger::Response &res, std::string chainName) { 00036 canopen::init(deviceFile, canopen::syncInterval); 00037 for (auto device : canopen::devices) 00038 canopen::sendSDO(device.second.CANid_, canopen::modes_of_operation, 00039 canopen::modes_of_operation_interpolated_position_mode); 00040 res.success.data = true; 00041 res.error_message.data = ""; 00042 return true; 00043 } 00044 00045 bool CANopenRecover(cob_srvs::Trigger::Request &req, 00046 cob_srvs::Trigger::Response &res, std::string chainName) { 00047 canopen::init(deviceFile, canopen::syncInterval); 00048 for (auto device : canopen::devices) 00049 canopen::sendSDO(device.second.CANid_, canopen::modes_of_operation, 00050 canopen::modes_of_operation_interpolated_position_mode); 00051 res.success.data = true; 00052 res.error_message.data = ""; 00053 return true; 00054 } 00055 00056 00057 bool setOperationModeCallback(cob_srvs::SetOperationMode::Request &req, 00058 cob_srvs::SetOperationMode::Response &res, std::string chainName) { 00059 res.success.data = true; // for now this service is just a dummy, not used elsewhere 00060 return true; 00061 } 00062 00063 void setVel(const brics_actuator::JointVelocities &msg, std::string chainName) { 00064 if (!canopen::atFirstInit) { 00065 std::vector<double> velocities; 00066 for (auto it : msg.velocities) 00067 velocities.push_back( it.value); 00068 canopen::deviceGroups[chainName].setVel(velocities); 00069 } 00070 } 00071 00072 void readParamsFromParameterServer(ros::NodeHandle n) { 00073 XmlRpc::XmlRpcValue busParams; 00074 00075 if (!n.hasParam("devices") || !n.hasParam("chains")) { 00076 ROS_ERROR("Missing parameters on parameter server; shutting down node."); 00077 ROS_ERROR("Please consult the user manual for necessary parameter settings."); 00078 n.shutdown(); 00079 } 00080 00081 n.getParam("devices", busParams); 00082 for (int i=0; i<busParams.size(); i++) { 00083 BusParams busParam; 00084 auto name = static_cast<std::string>(busParams[i]["name"]); 00085 busParam.baudrate = static_cast<std::string>(busParams[i]["baudrate"]); 00086 busParam.syncInterval = static_cast<int>(busParams[i]["sync_interval"]); 00087 buses[name] = busParam; 00088 } 00089 00090 XmlRpc::XmlRpcValue chainNames_XMLRPC; 00091 n.getParam("chains", chainNames_XMLRPC); 00092 std::vector<std::string> chainNames; 00093 for (int i=0; i<chainNames_XMLRPC.size(); i++) 00094 chainNames.push_back(static_cast<std::string>(chainNames_XMLRPC[i])); 00095 00096 for (auto chainName : chainNames) { 00097 XmlRpc::XmlRpcValue jointNames_XMLRPC; 00098 n.getParam("/" + chainName + "/joint_names", jointNames_XMLRPC); 00099 std::vector<std::string> jointNames; 00100 for (int i=0; i<jointNames_XMLRPC.size(); i++) 00101 jointNames.push_back(static_cast<std::string>(chainNames_XMLRPC[i])); 00102 00103 XmlRpc::XmlRpcValue moduleIDs_XMLRPC; 00104 n.getParam("/" + chainName + "/module_ids", moduleIDs_XMLRPC); 00105 std::vector<uint8_t> moduleIDs; 00106 for (int i=0; i<moduleIDs_XMLRPC.size(); i++) 00107 moduleIDs.push_back(static_cast<int>(moduleIDs_XMLRPC[i])); 00108 00109 XmlRpc::XmlRpcValue devices_XMLRPC; 00110 n.getParam("/" + chainName + "/devices", devices_XMLRPC); 00111 std::vector<std::string> devices; 00112 for (int i=0; i<devices_XMLRPC.size(); i++) 00113 devices.push_back(static_cast<std::string>(devices_XMLRPC[i])); 00114 00115 for (int i=0; i<jointNames.size(); i++) 00116 canopen::devices[ moduleIDs[i] ] = 00117 canopen::Device(moduleIDs[i], jointNames[i], chainName, devices[i]); 00118 00119 canopen::deviceGroups[ chainName ] = canopen::DeviceGroup(moduleIDs, jointNames); 00120 } 00121 } 00122 00123 00124 int main(int argc, char **argv) 00125 { 00126 // todo: allow identical module IDs of modules when they are on different CAN buses 00127 00128 ros::init(argc, argv, "canopen_ros"); 00129 ros::NodeHandle n; // ("~"); 00130 00131 readParamsFromParameterServer(n); 00132 00133 std::cout << buses.begin()->second.syncInterval << std::endl; 00134 canopen::syncInterval = std::chrono::milliseconds( buses.begin()->second.syncInterval ); 00135 // ^ todo: this only works with a single CAN bus; add support for more buses! 00136 deviceFile = buses.begin()->first; 00137 std::cout << deviceFile << std::endl; 00138 // ^ todo: this only works with a single CAN bus; add support for more buses! 00139 00140 // add custom PDOs: 00141 canopen::sendPos = canopen::schunkDefaultPDOOutgoing; 00142 for (auto it : canopen::devices) { 00143 canopen::incomingPDOHandlers[ 0x180 + it.first ] = 00144 [it](const TPCANRdMsg m) { canopen::schunkDefaultPDO_incoming( it.first, m ); }; 00145 } 00146 00147 // set up services, subscribers, and publishers for each of the chains: 00148 std::vector<TriggerType> initCallbacks; 00149 std::vector<ros::ServiceServer> initServices; 00150 std::vector<TriggerType> recoverCallbacks; 00151 std::vector<ros::ServiceServer> recoverServices; 00152 std::vector<SetOperationModeCallbackType> setOperationModeCallbacks; 00153 std::vector<ros::ServiceServer> setOperationModeServices; 00154 00155 std::vector<JointVelocitiesType> jointVelocitiesCallbacks; 00156 std::vector<ros::Subscriber> jointVelocitiesSubscribers; 00157 std::map<std::string, ros::Publisher> currentOperationModePublishers; 00158 std::map<std::string, ros::Publisher> statePublishers; 00159 ros::Publisher jointStatesPublisher = 00160 n.advertise<sensor_msgs::JointState>("/joint_states", 100); 00161 00162 for (auto it : canopen::deviceGroups) { 00163 std::cout << it.first << std::endl; 00164 00165 initCallbacks.push_back( boost::bind(CANopenInit, _1, _2, it.first) ); 00166 initServices.push_back 00167 (n.advertiseService("/" + it.first + "/init", initCallbacks.back()) ); 00168 recoverCallbacks.push_back( boost::bind(CANopenInit, _1, _2, it.first) ); 00169 recoverServices.push_back 00170 (n.advertiseService("/" + it.first + "/recover", recoverCallbacks.back()) ); 00171 setOperationModeCallbacks.push_back( boost::bind(setOperationModeCallback, _1, _2, it.first) ); 00172 setOperationModeServices.push_back( n.advertiseService("/" + it.first + "/set_operation_mode", setOperationModeCallbacks.back()) ); 00173 00174 jointVelocitiesCallbacks.push_back( boost::bind(setVel, _1, it.first) ); 00175 jointVelocitiesSubscribers.push_back 00176 (n.subscribe<brics_actuator::JointVelocities> 00177 ("/" + it.first + "/command_vel", 100, jointVelocitiesCallbacks.back()) ); 00178 00179 currentOperationModePublishers[it.first] = 00180 n.advertise<std_msgs::String> 00181 ("/" + it.first + "/current_operationmode", 1000); 00182 00183 statePublishers[it.first] = 00184 n.advertise<pr2_controllers_msgs::JointTrajectoryControllerState> 00185 ("/" + it.first + "/state", 1000); 00186 } 00187 00188 double lr = 1000.0 / std::chrono::duration_cast 00189 <std::chrono::milliseconds>(canopen::syncInterval).count(); 00190 std::cout << "Loop rate: " << lr << std::endl; 00191 ros::Rate loop_rate(lr); 00192 00193 canopen::initDeviceManagerThread(canopen::deviceManager); 00194 00195 while (ros::ok()) { 00196 00197 // iterate over all chains, get current pos and vel and publish as topics: 00198 for (auto dg : (canopen::deviceGroups)) { 00199 sensor_msgs::JointState js; 00200 js.name = dg.second.names_; 00201 js.header.stamp = ros::Time::now(); // todo: possibly better use timestamp of hardware msg? 00202 js.position = dg.second.getActualPos(); 00203 js.velocity = dg.second.getActualVel(); 00204 js.effort = std::vector<double>(dg.second.names_.size(), 0.0); 00205 jointStatesPublisher.publish(js); 00206 00207 pr2_controllers_msgs::JointTrajectoryControllerState jtcs; 00208 jtcs.header.stamp = js.header.stamp; 00209 jtcs.actual.positions = js.position; 00210 jtcs.actual.velocities = js.velocity; 00211 jtcs.desired.positions = dg.second.getDesiredPos(); 00212 jtcs.desired.velocities = dg.second.getDesiredVel(); 00213 statePublishers[dg.first].publish(jtcs); 00214 00215 std_msgs::String opmode; 00216 opmode.data = "velocity"; 00217 currentOperationModePublishers[dg.first].publish(opmode); 00218 } 00219 00220 ros::spinOnce(); 00221 loop_rate.sleep(); 00222 } 00223 00224 return 0; 00225 } 00226