Skip to content
This repository was archived by the owner on Dec 1, 2020. It is now read-only.

Commit 26e2044

Browse files
committed
Merge branch 'develop'
2 parents ef14b8f + 3876beb commit 26e2044

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

51 files changed

+1465
-216
lines changed

.travis.yml

+1-1
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ env:
3333
- CI_ENV=`bash <(curl -s https://codecov.io/env)`
3434
- DOCKER_RUN_OPTS='$CI_ENV'
3535
- TARGET_CMAKE_ARGS='-DCMAKE_BUILD_TYPE=Debug -DENABLE_COVERAGE_TESTING=ON'
36-
- UPSTREAM_WORKSPACE='.rosinstall -march/march_data_collector -march/march_gait_scheduler -march/march_gain_scheduling -march/march_gait_selection -march/march_launch -march/march_safety -march/march_state_machine'
36+
- UPSTREAM_WORKSPACE='.rosinstall -march/march_data_collector -march/march_gain_scheduling -march/march_gait_scheduler -march/march_gait_selection -march/march_launch -march/march_moveit -march/march_safety -march/march_shared_classes -march/march_state_machine'
3737
- AFTER_RUN_TARGET_TEST='cd "$target_ws" && bash <(curl -s https://codecov.io/bash) -R src/hardware-interface -F test && bash <(curl -s https://codecov.io/bash) -R src/hardware-interface -F production'
3838

3939
jobs:

march_hardware/CMakeLists.txt

+4-5
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
cmake_minimum_required(VERSION 2.8.3)
1+
cmake_minimum_required(VERSION 3.0.2)
22
project(march_hardware)
33

44
add_compile_options(-std=c++14 -Wall -Wextra -Werror)
@@ -12,6 +12,9 @@ find_package(catkin REQUIRED COMPONENTS
1212
catkin_package(
1313
INCLUDE_DIRS include
1414
CATKIN_DEPENDS
15+
roscpp
16+
soem
17+
urdf
1518
LIBRARIES ${PROJECT_NAME}
1619
CFG_EXTRAS
1720
${PROJECT_NAME}-extras.cmake
@@ -93,10 +96,6 @@ install(DIRECTORY include/${PROJECT_NAME}/
9396
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
9497
)
9598

96-
install(DIRECTORY include/${PROJECT_NAME}/
97-
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
98-
)
99-
10099
install(TARGETS ${PROJECT_NAME}
101100
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
102101
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}

march_hardware/include/march_hardware/error/error_type.h

+1
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ enum class ErrorType
3131
MISSING_REQUIRED_KEY = 119,
3232
INIT_URDF_FAILED = 120,
3333
INVALID_SW_STRING = 121,
34+
SLAVE_LOST_TIMOUT = 122,
3435
UNKNOWN = 999,
3536
};
3637

march_hardware/include/march_hardware/error/motion_error.h

+10-2
Original file line numberDiff line numberDiff line change
@@ -9,15 +9,23 @@ namespace march
99
{
1010
namespace error
1111
{
12+
enum class ErrorRegisters
13+
{
14+
MOTION_ERROR,
15+
DETAILED_ERROR,
16+
SECOND_DETAILED_ERROR
17+
};
18+
1219
const size_t MOTION_ERRORS_SIZE = 16;
1320
extern const char* MOTION_ERRORS[MOTION_ERRORS_SIZE];
1421

1522
const size_t DETAILED_MOTION_ERRORS_SIZE = 9;
1623
extern const char* DETAILED_MOTION_ERRORS[DETAILED_MOTION_ERRORS_SIZE];
1724

18-
std::string parseMotionError(uint16_t motion_error);
25+
const size_t SECOND_DETAILED_MOTION_ERROR_SIZE = 7;
26+
extern const char* SECOND_DETAILED_MOTION_ERRORS[SECOND_DETAILED_MOTION_ERROR_SIZE];
1927

20-
std::string parseDetailedError(uint16_t detailed_error);
28+
std::string parseError(uint16_t error, ErrorRegisters);
2129

2230
} // namespace error
2331
} // namespace march

march_hardware/include/march_hardware/ethercat/ethercat_master.h

+25-3
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
#ifndef MARCH_HARDWARE_ETHERCAT_ETHERCATMASTER_H
33
#define MARCH_HARDWARE_ETHERCAT_ETHERCATMASTER_H
44
#include <atomic>
5+
#include <exception>
56
#include <vector>
67
#include <string>
78
#include <thread>
@@ -23,7 +24,7 @@ namespace march
2324
class EthercatMaster
2425
{
2526
public:
26-
EthercatMaster(std::string ifname, int max_slave_index, int cycle_time);
27+
EthercatMaster(std::string ifname, int max_slave_index, int cycle_time, int slave_timeout);
2728
~EthercatMaster();
2829

2930
/* Delete copy constructor/assignment since the member thread can not be copied */
@@ -37,6 +38,8 @@ class EthercatMaster
3738
bool isOperational() const;
3839
void waitForPdo();
3940

41+
std::exception_ptr getLastException() const noexcept;
42+
4043
/**
4144
* Returns the cycle time in milliseconds.
4245
*/
@@ -75,13 +78,27 @@ class EthercatMaster
7578

7679
/**
7780
* Sends the PDO and receives the working counter and check if this is lower than expected.
81+
*
82+
* @returns true if and only if all PDOs have been successfully sent and received, otherwise false.
7883
*/
79-
void sendReceivePdo();
84+
bool sendReceivePdo();
8085

8186
/**
8287
* Checks if all the slaves are connected and in operational state.
8388
*/
84-
static void monitorSlaveConnection();
89+
void monitorSlaveConnection();
90+
91+
/**
92+
* Attempts to recover a slave to operational state.
93+
*
94+
* @returns true when recovery was successfull, otherwise false.
95+
*/
96+
bool attemptSlaveRecover(int slave);
97+
98+
/**
99+
* Sets ethercat state to INIT and closes port.
100+
*/
101+
void closeEthercat();
85102

86103
/**
87104
* Sets the ethercat thread priority and scheduling
@@ -105,7 +122,12 @@ class EthercatMaster
105122
char io_map_[4096] = { 0 };
106123
int expected_working_counter_ = 0;
107124

125+
int latest_lost_slave_ = -1;
126+
const int slave_watchdog_timeout_;
127+
std::chrono::high_resolution_clock::time_point valid_slaves_timestamp_ms_;
128+
108129
std::thread ethercat_thread_;
130+
std::exception_ptr last_exception_;
109131
};
110132

111133
} // namespace march

march_hardware/include/march_hardware/ethercat/pdo_map.h

+1
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@ enum class IMCObjectName
4747
ActualVelocity,
4848
MotionErrorRegister,
4949
DetailedErrorRegister,
50+
SecondDetailedErrorRegister,
5051
DCLinkVoltage,
5152
DriveTemperature,
5253
ActualTorque,

march_hardware/include/march_hardware/imotioncube/imotioncube.h

+2-1
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ class IMotionCube : public Slave
5757
uint16_t getStatusWord();
5858
uint16_t getMotionError();
5959
uint16_t getDetailedError();
60+
uint16_t getSecondDetailedError();
6061

6162
ActuationMode getActuationMode() const;
6263

@@ -120,7 +121,7 @@ class IMotionCube : public Slave
120121
* @param end_address the found end address of the setup in the .sw file
121122
* @return the computed checksum in the .sw file
122123
*/
123-
uint32_t computeSWCheckSum(int& start_address, int& end_address);
124+
uint16_t computeSWCheckSum(uint16_t& start_address, uint16_t& end_address);
124125
/**
125126
* Compares the checksum of the .sw file and the setup on the drive. If both are equal 1 is returned.
126127
* This method makes use of the computeSWCheckSum(int&, int&) method. The start and end addresses are used in

march_hardware/include/march_hardware/imotioncube/imotioncube_state.h

+4-1
Original file line numberDiff line numberDiff line change
@@ -125,11 +125,14 @@ struct IMotionCubeState
125125
IMotionCubeState() = default;
126126

127127
std::string statusWord;
128-
std::string detailedError;
129128
std::string motionError;
129+
std::string detailedError;
130+
std::string secondDetailedError;
130131
IMCState state;
131132
std::string detailedErrorDescription;
132133
std::string motionErrorDescription;
134+
std::string secondDetailedErrorDescription;
135+
133136
float motorCurrent;
134137
float IMCVoltage;
135138
float motorVoltage;

march_hardware/include/march_hardware/joint.h

+1
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,7 @@ class Joint
5555

5656
double getPosition() const;
5757
double getVelocity() const;
58+
double getVoltageVelocity() const;
5859
double getIncrementalPosition() const;
5960
double getAbsolutePosition() const;
6061
int16_t getTorque();

march_hardware/include/march_hardware/march_robot.h

+6-2
Original file line numberDiff line numberDiff line change
@@ -26,10 +26,12 @@ class MarchRobot
2626
public:
2727
using iterator = std::vector<Joint>::iterator;
2828

29-
MarchRobot(::std::vector<Joint> jointList, urdf::Model urdf, ::std::string ifName, int ecatCycleTime);
29+
MarchRobot(::std::vector<Joint> jointList, urdf::Model urdf, ::std::string ifName, int ecatCycleTime,
30+
int ecatSlaveTimeout);
3031

3132
MarchRobot(::std::vector<Joint> jointList, urdf::Model urdf,
32-
std::unique_ptr<PowerDistributionBoard> powerDistributionBoard, ::std::string ifName, int ecatCycleTime);
33+
std::unique_ptr<PowerDistributionBoard> powerDistributionBoard, ::std::string ifName, int ecatCycleTime,
34+
int ecatSlaveTimeout);
3335

3436
~MarchRobot();
3537

@@ -53,6 +55,8 @@ class MarchRobot
5355

5456
bool isEthercatOperational();
5557

58+
std::exception_ptr getLastEthercatException() const noexcept;
59+
5660
void waitForPdo();
5761

5862
int getEthercatCycleTime() const;

march_hardware/package.xml

+2-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
<?xml version="1.0"?>
2-
<package format="2">
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
34
<name>march_hardware</name>
45
<version>0.0.0</version>
56
<description>

march_hardware/src/error/error_type.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,8 @@ const char* getErrorDescription(ErrorType type)
5151
return "Failed to load URDF from parameter server";
5252
case ErrorType::INVALID_SW_STRING:
5353
return "Slave has incorrect SW file";
54+
case ErrorType::SLAVE_LOST_TIMOUT:
55+
return "EtherCAT slave monitor timer elapsed, connection has been lost";
5456
default:
5557
return "Unknown error occurred. Please create/use a documented error";
5658
}

march_hardware/src/error/motion_error.cpp

+27-17
Original file line numberDiff line numberDiff line change
@@ -36,29 +36,39 @@ const char* DETAILED_MOTION_ERRORS[DETAILED_MOTION_ERRORS_SIZE] = {
3636
"Invalid S-curve profile. ",
3737
};
3838

39-
std::string parseMotionError(uint16_t motion_error)
40-
{
41-
std::string description;
42-
const std::bitset<16> bitset(motion_error);
43-
for (size_t i = 0; i < MOTION_ERRORS_SIZE; i++)
44-
{
45-
if (bitset.test(i))
46-
{
47-
description += MOTION_ERRORS[i];
48-
}
49-
}
50-
return description;
51-
}
39+
const char* SECOND_DETAILED_MOTION_ERRORS[SECOND_DETAILED_MOTION_ERROR_SIZE] = {
40+
"BiSS data CRC error. ",
41+
"BiSS data warning bit is set. ",
42+
"BiSS data error bit is set. ",
43+
"BiSS sensor missing. ",
44+
"Absolute Encoder Interface (AEI) interface error. ",
45+
"Hall sensor missing. ",
46+
"Position wraparound. The position 2^31 was exceeded. ",
47+
};
5248

53-
std::string parseDetailedError(uint16_t detailed_error)
49+
std::string parseError(uint16_t error, ErrorRegisters error_register)
5450
{
5551
std::string description;
56-
const std::bitset<16> bitset(detailed_error);
57-
for (size_t i = 0; i < DETAILED_MOTION_ERRORS_SIZE; i++)
52+
const std::bitset<16> bitset(error);
53+
54+
for (size_t i = 0; i < 16; i++)
5855
{
5956
if (bitset.test(i))
6057
{
61-
description += DETAILED_MOTION_ERRORS[i];
58+
switch (error_register)
59+
{
60+
case ErrorRegisters::MOTION_ERROR:
61+
description += MOTION_ERRORS[i];
62+
break;
63+
case ErrorRegisters::DETAILED_ERROR:
64+
description += DETAILED_MOTION_ERRORS[i];
65+
break;
66+
case ErrorRegisters::SECOND_DETAILED_ERROR:
67+
description += SECOND_DETAILED_MOTION_ERRORS[i];
68+
break;
69+
default:
70+
break;
71+
}
6272
}
6373
}
6474
return description;

0 commit comments

Comments
 (0)