34 #include <boost/filesystem.hpp> 35 #include <boost/regex.hpp> 38 namespace canopen_schunk {
42 const std::string& resource_folder_location
44 : m_can_device_name(can_device_identifier),
45 m_can_device_flags(O_RDWR|O_NONBLOCK),
46 m_can_device_acceptance_code(0xff),
47 m_can_device_acceptance_mask(0xff),
48 m_can_device_send_fifo_size(300),
49 m_can_device_receive_fifo_size(2000),
50 m_can_device_baud_rate(baud_rate),
52 m_polling_period_ms(1),
53 m_resource_folder_location(resource_folder_location),
54 m_ws_broadcast_counter(0),
55 m_ws_broadcast_rate(5)
71 for (std::map<uint8_t, DS301Node::Ptr>::iterator it =
m_nodes.begin(); it !=
m_nodes.end(); ++it)
73 if (it->first == node_id || node_id < 0)
75 it->second->initNode();
86 "Message id: " << msg.
id <<
endl 87 <<
"Message length: " << msg.
dlc <<
endl 94 "Message id: " << msg.
id <<
endl 101 "Message id: " << msg.
id <<
endl 108 node->m_emcy->update(msg);
110 catch (
const std::exception& e)
112 LOGGING_ERROR (CanOpen,
"Exception thrown in EMCY update function: " << e.what() <<
endl);
120 "Message id: " << msg.
id <<
endl 127 "Message id: " << msg.
id <<
endl 134 node->m_tpdos.at(0)->update(msg);
136 catch (
const std::exception& e)
138 LOGGING_ERROR (CanOpen,
"Exception thrown in PDO update function: " << e.what() <<
endl);
146 "Message id: " << msg.
id <<
endl 153 "Message id: " << msg.
id <<
endl 160 node->m_tpdos.at(1)->update(msg);
162 catch (
const std::exception& e)
164 LOGGING_ERROR (CanOpen,
"Exception thrown in PDO update function: " << e.what() <<
endl);
172 "Message id: " << msg.
id <<
endl 179 "Message id: " << msg.
id <<
endl 186 node->m_tpdos.at(2)->update(msg);
188 catch (
const std::exception& e)
190 LOGGING_ERROR (CanOpen,
"Exception thrown in PDO update function: " << e.what() <<
endl);
198 "Message id: " << msg.
id <<
endl 205 "Message id: " << msg.
id <<
endl 212 node->m_tpdos.at(3)->update(msg);
214 catch (
const std::exception& e)
216 LOGGING_ERROR (CanOpen,
"Exception thrown in PDO update function: " << e.what() <<
endl);
224 "Message id: " << msg.
id <<
endl 231 "Message id: " << msg.
id <<
endl 238 node->m_sdo.update(msg);
250 "Message id: " << msg.
id <<
endl 257 node->m_sdo.update(msg);
269 "Message id: " << msg.
id <<
endl 278 node->m_nmt.update(msg);
284 if (msg.
data[0] != 0x0)
289 else if ( msg.
dlc == 1 && msg.
data[0] == 0x0)
322 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_ 324 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_ 342 std::vector<std::string> names;
343 boost::regex pattern(
"pcan(usb|pci)\\d+");
347 if ((dir = opendir(
"/dev")) != NULL)
350 while ((ent = readdir(dir)) != NULL)
352 std::string
s = ent->d_name;
353 if (boost::regex_match(s, pattern))
355 names.push_back(
"/dev/" + s);
362 bool can_found =
false;
365 for (
size_t num = 0; num < names.size() ; ++num)
384 std::stringstream ss;
401 LOGGING_ERROR(CanOpen,
" CAN DEVICE COULD NOT BE OPENED. \n >> Giving up.");
422 std::stringstream ss;
430 std::stringstream ss;
443 throw DeviceException(
"FATAL: Could not start listener thread for CAN bus.");
447 addGroup<DS402Group>(
"default");
455 std::map<std::string, DS301Group::Ptr>::iterator group_it;
456 group_it =
m_groups.find(sanitized_identifier);
459 std::vector<uint8_t> deleted_node_ids;
460 group_it->second->deleteNodes(deleted_node_ids);
463 for (std::vector<uint8_t>::iterator it = deleted_node_ids.begin();
464 it != deleted_node_ids.end();
468 std::map<uint8_t, DS301Node::Ptr>::iterator node_it =
m_nodes.find(*it);
469 assert(node_it->second.use_count() == 1);
478 <<
" exists. Not deleting anything." <<
endl);
485 for (std::map<std::string, DS301Group::Ptr>::iterator it =
m_groups.begin();
489 if (it->second->deleteNodeFromId(node_id))
497 std::map<uint8_t, DS301Node::Ptr>::iterator node_it =
m_nodes.find(node_id);
498 assert(node_it->second.use_count() == 1);
504 std::map<uint8_t, DS301Node::Ptr>::iterator node_it =
m_nodes.find(node_id);
508 " does not exist. Therefore this CAN message will be ignored." <<
endl);
512 return node_it->second;
521 char const* tmp = std::getenv(
"CANOPEN_RESOURCE_PATH");
527 "The environment variable 'CANOPEN_RESOURCE_PATH' could not be read. Using relative path 'resources/'" <<
endl);
528 resources_path = boost::filesystem::path(
"resources");
532 resources_path = boost::filesystem::path(tmp);
536 std::string sdo_errors_filename = (resources_path / boost::filesystem::path(
"SDO.ini")).
string();
539 std::string emcy_emergency_errors_filename = (resources_path / boost::filesystem::path(
"EMCY.ini")).
string();
543 emcy_emergency_errors_filename = (resources_path / boost::filesystem::path(
"EMCY_DS402.ini")).
string();
549 for (std::map<uint8_t, DS301Node::Ptr>::iterator it =
m_nodes.begin();
553 it->second->downloadPDOs();
558 for (std::map<uint8_t, DS301Node::Ptr>::iterator it =
m_nodes.begin();
562 it->second->uploadPDOs();
565 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_ 577 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_ 584 for (std::map<uint8_t, DS301Node::Ptr>::iterator it =
m_nodes.begin();
588 it->second->stopNode();
594 std::vector <uint8_t> node_list;
597 for (std::map<uint8_t, DS301Node::Ptr>::iterator it =
m_nodes.begin();
601 it->second->downloadPDOs();
602 node_list.push_back(it->second->getNodeId());
618 for (std::map<std::string, DS301Group::Ptr>::iterator it =
m_groups.begin();
625 group_ds402->startPPMovement(node_id);
632 for (std::map<std::string, DS301Group::Ptr>::iterator it =
m_groups.begin();
639 group_ds402->acceptPPTargets(node_id);
static const uint16_t ID_RSDO_MAX
static TimeSpan createFromMSec(int64_t msec)
static const uint16_t ID_TSDO_MAX
#define LOGGING_INFO_C(streamname, classname, arg)
static const uint16_t ID_RPDO1_MIN
static const uint16_t ID_RSDO_MIN
static const uint16_t ID_TPDO3_MIN
virtual const char * what() const _GLIBCXX_USE_NOEXCEPT
static void addEmergencyErrorMap(const std::string &filename, const std::string &block_identifier)
Adds new information from an ini file to the emergency error map.
boost::shared_ptr< DS301Node > Ptr
Shared pointer to a DS301Node.
std::string m_resource_folder_location
This folder contains for example the error code definitions.
size_t m_ws_broadcast_counter
std::string hexArrayToString(const unsigned char *msg, const uint8_t length)
Transforms an array of unsigned chars into a string of Hex representations of those chars...
#define LOGGING_INFO(streamname, arg)
size_t m_ws_broadcast_rate
Counts sync cycles.
void initNodes(const int16_t node_id=-1)
Initializes a node with a given ID or all nodes.
HeartBeatMonitor::Ptr m_heartbeat_monitor
void deleteNode(const uint8_t node_id)
Delete a node with a given CANOPEN-ID.
void getResources()
Load resources like error-code lookup maps.
static const uint16_t ID_TPDO2_MAX
std::vector< uint8_t > getNodeList()
Returns a list containing all used node ids.
virtual const char * what() const _GLIBCXX_USE_NOEXCEPT
static tCanDevice * Create(const char *device_name, int flags, unsigned char acceptance_code, unsigned char acceptance_mask, unsigned int baud_rate, unsigned send_fifo_size, unsigned receive_fifo_size)
std::map< uint8_t, DS301Node::Ptr > m_nodes
Map of all nodes with id identifier.
The DS402Group class is the base class for canOpen devices implementing the DS402 device protocol (mo...
static const uint16_t ID_TIME
uint32_t m_polling_period_ms
The CAN message polling period duration in milliseconds.
uint32_t m_can_device_receive_fifo_size
uint32_t m_can_device_baud_rate
static const uint16_t ID_NMT_ERROR_MAX
int32_t m_can_device_flags
#define LOGGING_WARNING_C(streamname, classname, arg)
static void sendSync(const CanDevPtr &can_device)
sendSync sends a SYNC message which is used to ensure synchronous processing of all CanOpen nodes...
#define LOGGING_ERROR(streamname, arg)
static const uint16_t ID_NMT_ERROR_MIN
The CanOpenController class is the main entry point for any calls to the canOpen System.
void processCanMsgCallback(const icl_hardware::can::tCanMessage &msg)
Incoming can messages are processed in this function and forwarded to the addressed node...
void enablePPMotion(const int16_t node_id=-1)
When using the ProfilePositionMode is used, in addition to setting the target motion has to be trigge...
std::map< std::string, DS301Group::Ptr > m_groups
Map of all node groups, with string identifier.
static const uint16_t ID_EMCY_MIN
static const uint16_t ID_EMCY_MAX
static const uint16_t ID_RPDO2_MIN
#define LOGGING_DEBUG_C(streamname, classname, arg)
Exceptions relating to device responses.
static const uint16_t ID_NMT
static const uint16_t ID_RPDO2_MAX
ThreadStream & endl(ThreadStream &stream)
static const uint16_t ID_TPDO4_MIN
The CanOpenReceiveThread class handles incoming canOpen messages.
unsigned char m_can_device_acceptance_mask
If something goes wrong with the host's CAN controller, this exception will be used.
uint32_t m_can_device_send_fifo_size
static const uint16_t ID_RPDO1_MAX
static const uint16_t ID_SYNC
void deleteGroup(const std::string &identifier)
Deletes a group with the given identifier. Also deletes all its nodes.
static const uint16_t ID_RPDO3_MAX
unsigned char m_can_device_acceptance_code
static const uint16_t ID_TPDO1_MAX
std::string m_can_device_name
CanOpenReceiveThreadPtr m_receive_thread
Handle for the can receive thread.
static void addErrorMapFromFile(const std::string &filename)
Adds an error map from an INI file to all SDOs. This should be called once to get human readable erro...
static const uint16_t ID_TPDO3_MAX
boost::shared_ptr< icl_comm::websocket::WsBroadcaster > m_ws_broadcaster
Interface to send out diagnostics data. Only available if compiled with IC_BUILDER_ICL_COMM_WEBSOCKET...
CanDevPtr m_can_device
Handle for the can device.
std::string sanitizeString(const std::string &text)
This function removes all non-graphical characters from the given string.
void stopAll()
Calls stop() on all registered nodes.
static const uint16_t ID_TSDO_MIN
static const uint16_t ID_TPDO4_MAX
static const uint16_t ID_RPDO4_MIN
static void addErrorRegisterMap(const std::string &filename, const std::string &block_identifier)
Adds new information from an ini file to the error_register map.
#define LOGGING_TRACE_C(streamname, classname, arg)
static const uint16_t ID_TPDO2_MIN
void reconnectCanDevice(const std::string &can_identifier, const uint32_t baud_rate)
Reconnects the CAN device with the given configuration.
CanOpenController(const std::string can_device_identifier="/dev/pcanusb0", const uint32_t baud_rate=500, const std::string &resource_folder_location="")
CanOpenController constructor.
DS301Node::Ptr getNodeById(const uint8_t node_id)
get a handle for a node identified by its CANOPEN-ID
static const uint16_t ID_RPDO4_MAX
#define LOGGING_ERROR_C(streamname, classname, arg)
void syncAll()
Downloads all the RPDOs, Sends a Sync and Uploads all the TPDOs.
static const uint16_t ID_RPDO3_MIN
int usleep(unsigned long useconds)
static const uint16_t ID_TPDO1_MIN