KaCanOpen
 All Classes Functions Variables Typedefs Enumerations Pages
core.cpp
1 /*
2  * Copyright (c) 2015-2016, Thomas Keh
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  *
15  * 3. Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include <chrono>
33 #include <vector>
34 #include <iostream>
35 
36 #include "core.h"
37 
38 int main() {
39 
40  // ----------- //
41  // Preferences //
42  // ----------- //
43 
44  // The node ID of the slave we want to communicate with.
45  const uint8_t node_id = 2;
46 
47  // Set the name of your CAN bus. "slcan0" is a common bus name
48  // for the first SocketCAN device on a Linux system.
49  const std::string busname = "slcan0";
50 
51  // Set the baudrate of your CAN bus. Most drivers support the values
52  // "1M", "500K", "125K", "100K", "50K", "20K", "10K" and "5K".
53  const std::string baudrate = "500K";
54 
55  // Set the object dictionary index to write to (download).
56  // Here: CiA-401 (I/O device) digital output.
57  const uint16_t index = 0x6200;
58 
59  // Alternative: CiA-402 (motor) control word:
60  //const uint16_t index = 0x6040;
61 
62  // Set the object dictionary sub-index to write to (download).
63  // Here: CiA-401 (I/O device) digital output - second byte.
64  const uint8_t subindex = 0x01;
65 
66  // Alternative: CiA-402 (motor) control word:
67  //const uint8_t subindex = 0x00;
68 
69  // Set the data to write (download).
70  const std::vector<uint8_t> data { 0x7F };
71 
72  // Alternative: CiA-402 (motor) control word has two bytes. Command: shutdown (little-endian!)
73  //const std::vector<uint8_t> data { 0x06, 0x00 };
74 
75  // -------------- //
76  // Initialization //
77  // -------------- //
78 
79  std::cout << "This is an example which shows the usage of the Core library." << std::endl;
80 
81  // Create core.
82  kaco::Core core;
83 
84  // This will be set to true by the callback below.
85  bool found_node = false;
86 
87  std::cout << "Registering a callback which is called when a device is detected via NMT..." << std::endl;
88  core.nmt.register_device_alive_callback([&] (const uint8_t new_node_id) {
89  std::cout << "Device says it's alive! ID = " << (unsigned) new_node_id << std::endl;
90  // Check if this is the node we are looking for.
91  if (new_node_id == node_id) {
92  found_node = true;
93  }
94  });
95 
96  std::cout << "Starting Core (connect to the driver and start the receiver thread)..." << std::endl;
97  if (!core.start(busname, baudrate)) {
98  std::cout << "Starting core failed." << std::endl;
99  return EXIT_FAILURE;
100  }
101 
102  std::cout << "Asking all devices to reset. You don't need to do that, but it makes"
103  << " sure all slaves are in a reproducible state." << std::endl;
104  core.nmt.reset_all_nodes();
105 
106  // As an alternative you can request the slaves to announce
107  // themselves:
108  // core.nmt.discover_nodes();
109 
110  std::cout << "Giving the devices one second time to respond..." << std::endl;
111  std::this_thread::sleep_for(std::chrono::seconds(1));
112 
113  // Check if the device has been detected (see the callback above).
114  if (!found_node) {
115  std::cout << "Node with ID " << (unsigned) node_id << " has not been found."<< std::endl;
116  return EXIT_FAILURE;
117  }
118 
119  std::cout << "Asking the device to start up..." << std::endl;
120  core.nmt.send_nmt_message(node_id,kaco::NMT::Command::start_node);
121 
122  std::cout << "Giving the devices one second time to boot up..." << std::endl;
123  std::this_thread::sleep_for(std::chrono::seconds(1));
124 
125  // ------------ //
126  // Device usage //
127  // ------------ //
128 
129  std::cout << "Writing to a dictionary entry (CANopen speech: \"download\")..." << std::endl;
130  core.sdo.download(node_id, index, subindex, data.size(), data);
131 
132  std::cout << "Reading the device type (\"upload\" 0x1000)... Little-endian!" << std::endl;
133  std::vector<uint8_t> device_type = core.sdo.upload(node_id,0x1000,0x0);
134  for (uint8_t device_type_byte : device_type) {
135  std::cout << " byte 0x" << std::hex << (unsigned) device_type_byte << std::endl;
136  }
137 
138  std::cout << "Reading the device name (\"upload\" 0x1008 - usually using segmented transfer)..." << std::endl;
139  std::vector<uint8_t> device_name = core.sdo.upload(node_id,0x1008,0x0);
140  std::string result(reinterpret_cast<char const*>(device_name.data()), device_name.size());
141  std::cout << " " << result << std::endl;
142 
143  std::cout << "Finished." << std::endl;
144  return EXIT_SUCCESS;
145 
146 }
void send_nmt_message(uint8_t node_id, Command cmd)
Sends a NMT message to a given device.
Definition: nmt.cpp:47
NMT nmt
The NMT sub-protocol.
Definition: core.h:109
void register_device_alive_callback(const DeviceAliveCallback &callback)
Registers a callback which will be called when a slave sends it's state via NMT and the state indicat...
Definition: nmt.cpp:181
void download(uint8_t node_id, uint16_t index, uint8_t subindex, uint32_t size, const std::vector< uint8_t > &bytes)
SDO download: Write value into remote device's object dictionary.
Definition: sdo.cpp:50
This class implements the Core of KaCanOpen It communicates with the CAN driver, sends CAN messages a...
Definition: core.h:59
SDO sdo
The SDO sub-protocol.
Definition: core.h:112
bool start(const std::string busname, const std::string &baudrate)
Opens CAN driver and starts CAN message receive loop.
Definition: core.cpp:84
std::vector< uint8_t > upload(uint8_t node_id, uint16_t index, uint8_t subindex)
SDO download: Get value from remote device's object dictionary.
Definition: sdo.cpp:84
void reset_all_nodes()
Resets all nodes in the network.
Definition: nmt.cpp:57