This is a ROS driver for Shadow Robot #6 EtherCAT Slave. More...
#include <sr_edc_ethercat_drivers/sr06.h>#include <dll/ethercat_dll.h>#include <al/ethercat_AL.h>#include <dll/ethercat_device_addressed_telegram.h>#include <dll/ethercat_frame.h>#include <realtime_tools/realtime_publisher.h>#include <math.h>#include <sstream>#include <iomanip>#include <boost/foreach.hpp>#include <std_msgs/Int16.h>#include <fcntl.h>#include <stdio.h>#include <pthread.h>#include <bfd.h>#include <sr_utilities/sr_math_utils.hpp>#include <sr_external_dependencies/types_for_external.h>#include <sr_external_dependencies/external/simplemotor-bootloader/bootloader.h>#include <boost/static_assert.hpp>
Go to the source code of this file.
Namespaces | |
| namespace | is_edc_command_32_bits |
Defines | |
| #define | check_for_pthread_mutex_init_error(x) |
| #define | check_for_trylock_error(x) |
| #define | ETHERCAT_CAN_BRIDGE_DATA_SIZE sizeof(ETHERCAT_CAN_BRIDGE_DATA) |
| #define | ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND) |
| #define | ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS) |
| #define | unlock(x) |
Functions | |
| is_edc_command_32_bits::BOOST_STATIC_ASSERT (sizeof(EDC_COMMAND)==4) | |
| PLUGINLIB_REGISTER_CLASS (6, SR06, EthercatDevice) | |
This is a ROS driver for Shadow Robot #6 EtherCAT Slave.
Copyright 2011 Shadow Robot Company Ltd.
This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 2 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 General Public License for more details.
You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>.
Definition in file sr06.cpp.
| #define check_for_pthread_mutex_init_error | ( | x | ) |
switch(x) \ { \ case EAGAIN: \ ROS_ERROR("The system temporarily lacks the resources to create another mutex : %s:%d", __FILE__, __LINE__); \ exit(1); \ break; \ case EINVAL: \ ROS_ERROR("The value specified as attribute is invalid for mutex init : %s:%d", __FILE__, __LINE__); \ exit(1); \ break; \ case ENOMEM: \ ROS_ERROR("The process cannot allocate enough memory to create another mutex : %s:%d", __FILE__, __LINE__); \ exit(1); \ break; \ case 0: /* SUCCESS */ \ break; \ default: \ ROS_ERROR("unknown error value, is this POSIX system ? : %s:%d", __FILE__, __LINE__); \ exit(1); \ }
| #define check_for_trylock_error | ( | x | ) |
| #define ETHERCAT_CAN_BRIDGE_DATA_SIZE sizeof(ETHERCAT_CAN_BRIDGE_DATA) |
| #define ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND) |
| #define ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS) |
| #define unlock | ( | x | ) |
switch ( pthread_mutex_unlock(x) ) \ { \ case EINVAL: \ ROS_ERROR("The value specified as a mutex is invalid : %s:%d", __FILE__, __LINE__); \ exit(1); \ break; \ case EPERM: \ ROS_ERROR("The current thread does not hold a lock on the mutex : %s:%d", __FILE__, __LINE__); \ exit(1); \ break; \ }
| PLUGINLIB_REGISTER_CLASS | ( | 6 | , |
| SR06 | , | ||
| EthercatDevice | |||
| ) |