KaCanOpen
 All Classes Functions Variables Typedefs Enumerations Pages
examples/listdevices.cpp

This example lists all connected devices and prints their manufacturer device name.

/*
* Copyright (c) 2015-2016, Thomas Keh
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <thread>
#include <chrono>
#include <cstdint>
#include "master.h"
#include "logger.h"
// This example lists all connected devices and prints their manufacturer device name.
int main() {
// Set the name of your CAN bus. "slcan0" is a common bus name
// for the first SocketCAN device on a Linux system.
const std::string busname = "slcan0";
// Set the baudrate of your CAN bus. Most drivers support the values
// "1M", "500K", "125K", "100K", "50K", "20K", "10K" and "5K".
const std::string baudrate = "500K";
PRINT("List devices");
kaco::Master master;
if (!master.start(busname, baudrate)) {
ERROR("Starting master failed.");
return EXIT_FAILURE;
}
std::this_thread::sleep_for(std::chrono::seconds(1));
const size_t num_devices = master.num_devices();
DUMP(num_devices);
for (size_t i=0; i<num_devices; ++i) {
kaco::Device& device = master.get_device(i);
PRINT("Found device: " << device.get_node_id());
PRINT("Starting");
device.start();
PRINT("Loading EDS from library...")
const std::string loaded_eds_file = device.load_dictionary_from_library();
PRINT("Loaded the following EDS file from the library: " << loaded_eds_file);
PRINT("Dictionary:");
device.print_dictionary();
}
}