Go to the documentation of this file.00001
00002 #include <canopen_motor_node/motor_chain.h>
00003 #include <canopen_motor_node/handle_layer.h>
00004
00005 using namespace canopen;
00006
00007
00008 class XmlRpcSettings : public Settings{
00009 public:
00010 XmlRpcSettings() {}
00011 XmlRpcSettings(const XmlRpc::XmlRpcValue &v) : value_(v) {}
00012 XmlRpcSettings& operator=(const XmlRpc::XmlRpcValue &v) { value_ = v; return *this; }
00013 private:
00014 virtual bool getRepr(const std::string &n, std::string & repr) const {
00015 if(value_.hasMember(n)){
00016 std::stringstream sstr;
00017 sstr << const_cast< XmlRpc::XmlRpcValue &>(value_)[n];
00018 repr = sstr.str();
00019 return true;
00020 }
00021 return false;
00022 }
00023 XmlRpc::XmlRpcValue value_;
00024
00025 };
00026
00027
00028 MotorChain::MotorChain(const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv) :
00029 RosChain(nh, nh_priv), motor_allocator_("canopen_402", "canopen::MotorBase::Allocator") {}
00030
00031 bool MotorChain::nodeAdded(XmlRpc::XmlRpcValue ¶ms, const boost::shared_ptr<canopen::Node> &node, const boost::shared_ptr<Logger> &logger)
00032 {
00033 std::string name = params["name"];
00034 std::string &joint = name;
00035 if(params.hasMember("joint")) joint.assign(params["joint"]);
00036
00037 if(!robot_layer_->getJoint(joint)){
00038 ROS_ERROR_STREAM("joint " + joint + " was not found in URDF");
00039 return false;
00040 }
00041
00042 std::string alloc_name = "canopen::Motor402::Allocator";
00043 if(params.hasMember("motor_allocator")) alloc_name.assign(params["motor_allocator"]);
00044
00045 XmlRpcSettings settings;
00046 if(params.hasMember("motor_layer")) settings = params["motor_layer"];
00047
00048 boost::shared_ptr<MotorBase> motor;
00049
00050 try{
00051 motor = motor_allocator_.allocateInstance(alloc_name, name + "_motor", node->getStorage(), settings);
00052 }
00053 catch( const std::exception &e){
00054 std::string info = boost::diagnostic_information(e);
00055 ROS_ERROR_STREAM(info);
00056 return false;
00057 }
00058
00059 if(!motor){
00060 ROS_ERROR_STREAM("Could not allocate motor.");
00061 return false;
00062 }
00063
00064 motor->registerDefaultModes(node->getStorage());
00065 motors_->add(motor);
00066 logger->add(motor);
00067
00068 boost::shared_ptr<HandleLayer> handle( new HandleLayer(joint, motor, node->getStorage(), params));
00069
00070 canopen::LayerStatus s;
00071 if(!handle->prepareFilters(s)){
00072 ROS_ERROR_STREAM(s.reason());
00073 return false;
00074 }
00075
00076 robot_layer_->add(joint, handle);
00077 logger->add(handle);
00078
00079 return true;
00080 }
00081
00082 bool MotorChain::setup_chain() {
00083 motors_.reset(new LayerGroupNoDiag<MotorBase>("402 Layer"));
00084 robot_layer_.reset(new RobotLayer(nh_));
00085
00086 ros::Duration dur(0.0) ;
00087
00088 if(RosChain::setup_chain()){
00089 add(motors_);
00090 add(robot_layer_);
00091
00092 if(!nh_.param("use_realtime_period", false)){
00093 dur.fromSec(boost::chrono::duration<double>(update_duration_).count());
00094 ROS_INFO_STREAM("Using fixed control period: " << dur);
00095 }else{
00096 ROS_INFO("Using real-time control period");
00097 }
00098 cm_.reset(new ControllerManagerLayer(robot_layer_, nh_, dur));
00099 add(cm_);
00100
00101 return true;
00102 }
00103
00104 return false;
00105 }
00106