Implementation of canopen. More...
#include "ros/ros.h"
#include <urdf/model.h>
#include "std_msgs/String.h"
#include "sensor_msgs/JointState.h"
#include "control_msgs/JointTrajectoryControllerState.h"
#include "brics_actuator/JointVelocities.h"
#include "cob_srvs/Trigger.h"
#include "cob_srvs/SetOperationMode.h"
#include <diagnostic_msgs/DiagnosticArray.h>
#include <iostream>
#include <map>
#include <boost/bind.hpp>
#include <boost/filesystem.hpp>
#include <ipa_canopen_core/canopen.h>
#include <XmlRpcValue.h>
#include <ipa_canopen_ros/JointLimits.h>
Go to the source code of this file.
Classes | |
struct | BusParams |
Typedefs | |
typedef boost::function< void(const brics_actuator::JointVelocities &)> | JointVelocitiesType |
typedef boost::function< bool(cob_srvs::SetOperationMode::Request &, cob_srvs::SetOperationMode::Response &)> | SetOperationModeCallbackType |
typedef boost::function< bool(cob_srvs::Trigger::Request &, cob_srvs::Trigger::Response &)> | TriggerType |
Functions | |
bool | CANOpenHalt (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res, std::string chainName) |
bool | CANopenInit (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res, std::string chainName) |
bool | CANopenRecover (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res, std::string chainName) |
int | main (int argc, char **argv) |
void | readParamsFromParameterServer (ros::NodeHandle n) |
void | setJointConstraints (ros::NodeHandle n) |
bool | setOperationModeCallback (cob_srvs::SetOperationMode::Request &req, cob_srvs::SetOperationMode::Response &res, std::string chainName) |
void | setVel (const brics_actuator::JointVelocities &msg, std::string chainName) |
Variables | |
std::vector< std::string > | chainNames |
std::string | deviceFile |
std::map< std::string, JointLimits * > | joint_limits |
std::vector< int > | motor_direction |
Implementation of canopen.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
This program is free software: you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License LGPL as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License LGPL for more details.
You should have received a copy of the GNU Lesser General Public License LGPL along with this program. If not, see <http://www.gnu.org/licenses/>.
Definition in file ipa_canopen_ros.cpp.
typedef boost::function<void(const brics_actuator::JointVelocities&)> JointVelocitiesType |
Definition at line 78 of file ipa_canopen_ros.cpp.
typedef boost::function<bool(cob_srvs::SetOperationMode::Request&, cob_srvs::SetOperationMode::Response&)> SetOperationModeCallbackType |
Definition at line 79 of file ipa_canopen_ros.cpp.
typedef boost::function<bool(cob_srvs::Trigger::Request&, cob_srvs::Trigger::Response&)> TriggerType |
Definition at line 77 of file ipa_canopen_ros.cpp.
bool CANOpenHalt | ( | cob_srvs::Trigger::Request & | req, |
cob_srvs::Trigger::Response & | res, | ||
std::string | chainName | ||
) |
Definition at line 184 of file ipa_canopen_ros.cpp.
bool CANopenInit | ( | cob_srvs::Trigger::Request & | req, |
cob_srvs::Trigger::Response & | res, | ||
std::string | chainName | ||
) |
Definition at line 98 of file ipa_canopen_ros.cpp.
bool CANopenRecover | ( | cob_srvs::Trigger::Request & | req, |
cob_srvs::Trigger::Response & | res, | ||
std::string | chainName | ||
) |
Definition at line 144 of file ipa_canopen_ros.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 549 of file ipa_canopen_ros.cpp.
void readParamsFromParameterServer | ( | ros::NodeHandle | n | ) |
Definition at line 237 of file ipa_canopen_ros.cpp.
void setJointConstraints | ( | ros::NodeHandle | n | ) |
Get robot_description from ROS parameter server
Get urdf model out of robot_description
Get max velocities out of urdf model
Get lower limits out of urdf model
Get offsets out of urdf model
Set parameters
Definition at line 419 of file ipa_canopen_ros.cpp.
bool setOperationModeCallback | ( | cob_srvs::SetOperationMode::Request & | req, |
cob_srvs::SetOperationMode::Response & | res, | ||
std::string | chainName | ||
) |
Definition at line 198 of file ipa_canopen_ros.cpp.
void setVel | ( | const brics_actuator::JointVelocities & | msg, |
std::string | chainName | ||
) |
Definition at line 204 of file ipa_canopen_ros.cpp.
std::vector<std::string> chainNames |
Definition at line 96 of file ipa_canopen_ros.cpp.
std::string deviceFile |
Definition at line 94 of file ipa_canopen_ros.cpp.
std::map<std::string, JointLimits*> joint_limits |
Definition at line 83 of file ipa_canopen_ros.cpp.
std::vector<int> motor_direction |
Definition at line 81 of file ipa_canopen_ros.cpp.