Skip to content
This repository has been archived by the owner on Nov 10, 2022. It is now read-only.

Commit

Permalink
create release-v.0.5. Everything worked as expected
Browse files Browse the repository at this point in the history
  • Loading branch information
csl-pc104 committed May 14, 2019
1 parent 25dd6ce commit 22326db
Show file tree
Hide file tree
Showing 9 changed files with 89,024 additions and 168,561 deletions.
2 changes: 1 addition & 1 deletion config/ethercat_slaves.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,6 @@ ethercat_slaves :
assign_activate: 0x0700
input_port: 0x6010
output_port: 0x7000
period_ns: 400000
period_ns: 1000000
run_time: 360000
sync0_shift: 55000
10 changes: 6 additions & 4 deletions include/ether_ros/ether_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@
Assumes that the EtherCAT application is the same for every slave.
*/
/** \var int log_fd
\brief File descriptor used for logging, provided that TIMING_SAMPLING is enabled.
\brief File descriptor used for logging, provided that LOGGING and one of LOGGING_SAMPLING or LOGGING_NO_SAMPLING is enabled.
Could be deprecated in a next version (see kernelshark).
*/
Expand Down Expand Up @@ -131,7 +131,7 @@
/** \def SAMPLING_FREQ 10
\brief The sampling frequency.
Used when the \a TIMING_SAMPLING is defined.
Used when the \a LOGGING_SAMPLING is defined.
It's used as a frequency for sampling measurements.
The number is in Hz.
*/
Expand Down Expand Up @@ -198,9 +198,9 @@

// Application parameters
#define CLOCK_TO_USE CLOCK_MONOTONIC
// #define TIMING_SAMPLING 0
// #define LOGGING_SAMPLING
// #define RUN_TIME 60 // run time in seconds
#if TIMING_SAMPLING
#if defined(LOGGING) && defined(LOGGING_SAMPLING)
#define SAMPLING_FREQ 10
#endif
/****************************************************************************/
Expand Down Expand Up @@ -260,5 +260,7 @@ extern PDOOutPublisherTimer pdo_out_publisher_timer;
extern int PERIOD_NS;
extern int FREQUENCY;
extern int RUN_TIME;
#ifdef LOGGING
extern statistics_struct stat_struct;
#endif
#endif /* ether_ros_LIB_H */
11 changes: 7 additions & 4 deletions include/ether_ros/ethercat_communicator.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,8 @@
#define FIFO_SCHEDULING //the default scheduling policy will be FIFO

#endif
#if TIMING_SAMPLING
#ifdef LOGGING
#ifdef LOGGING_SAMPLING

typedef struct statistics_struct
{
Expand All @@ -77,8 +78,8 @@ typedef struct statistics_struct
struct timespec end_time;
struct timespec last_start_time;
} statistics_struct;

#elif TIMING_SAMPLING == 0
#endif
#ifdef LOGGING_NO_SAMPLING

typedef struct statistics_struct
{
Expand All @@ -91,6 +92,7 @@ typedef struct statistics_struct
struct timespec last_start_time;
} statistics_struct;
#endif
#endif
class EthercatCommunicator
{
private:
Expand Down Expand Up @@ -122,10 +124,11 @@ class EthercatCommunicator
static void sync_distributed_clocks(void);
static void update_master_clock(void);
static uint64_t system_time_ns(void);
#ifdef LOGGING
static void create_new_statistics_sample(statistics_struct *ss, unsigned int * sampling_counter);
static void create_statistics(statistics_struct * ss, struct timespec * wakeup_time_p);
static void log_statistics_to_file(statistics_struct *ss);

#endif
public:
/** \fn static bool has_running_thread()
\brief A getter for knowing if there is a running thread.
Expand Down
12 changes: 6 additions & 6 deletions scripts/optimizations/optimizations.sh
Original file line number Diff line number Diff line change
Expand Up @@ -71,12 +71,12 @@ do
echo $i; echo $i > /sys/fs/cgroup/cpuset/nrt/tasks;
done

# enp5s0_irq_pid=$(ps -e | grep "enp5s0$" | grep -o -E '[0-9]+' | head -n 1)
# echo $enp5s0_irq_pid; echo $enp5s0_irq_pid > /sys/fs/cgroup/cpuset/rt/tasks;
# enp5s0_r_irq_pid=$(ps -e | grep "enp5s0-r" | grep -o -E '[0-9]+' | head -n 1)
# echo $enp5s0_r_irq_pid; echo $enp5s0_r_irq_pid > /sys/fs/cgroup/cpuset/rt/tasks;
# enp5s0_t_irq_pid=$(ps -e | grep "enp5s0-t" | grep -o -E '[0-9]+' | head -n 1)
# echo $enp5s0_t_irq_pid; echo $enp5s0_t_irq_pid > /sys/fs/cgroup/cpuset/rt/tasks;
enp5s0_irq_pid=$(ps -e | grep "enp5s0$" | grep -o -E '[0-9]+' | head -n 1)
echo $enp5s0_irq_pid; echo $enp5s0_irq_pid > /sys/fs/cgroup/cpuset/rt/tasks;
enp5s0_r_irq_pid=$(ps -e | grep "enp5s0-r" | grep -o -E '[0-9]+' | head -n 1)
echo $enp5s0_r_irq_pid; echo $enp5s0_r_irq_pid > /sys/fs/cgroup/cpuset/rt/tasks;
enp5s0_t_irq_pid=$(ps -e | grep "enp5s0-t" | grep -o -E '[0-9]+' | head -n 1)
echo $enp5s0_t_irq_pid; echo $enp5s0_t_irq_pid > /sys/fs/cgroup/cpuset/rt/tasks;
# etherlab_pid=$(ps -e | grep "EtherCAT-IDLE" | grep -o -E '[0-9]+' | head -n 1)
# echo $etherlab_pid; echo $etherlab_pid > /sys/fs/cgroup/cpuset/rt/tasks;

Expand Down
257,448 changes: 88,941 additions & 168,507 deletions scripts/trace-cmd/output.txt

Large diffs are not rendered by default.

11 changes: 6 additions & 5 deletions scripts/trace-cmd/trace_01.sh
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
#!/bin/bash
enp5s0_irq_pid=$(ps -e | grep "enp0s25$" | grep -o -E '[0-9]+' | head -n 1);
# enp5s0_r_irq_pid=$(ps -e | grep "enp5s0-r" | grep -o -E '[0-9]+' | head -n 1);
# enp5s0_t_irq_pid=$(ps -e | grep "enp5s0-t" | grep -o -E '[0-9]+' | head -n 1);
etherlab_pid=$(ps -e | grep "EtherCAT-IDLE" | grep -o -E '[0-9]+' | head -n 1);
ksoftirqd3_pid=$(ps -e | grep "ksoftirqd/1" | grep -o -E '[0-9]+' | head -n 1);
enp5s0_r_irq_pid=$(ps -e | grep "enp5s0-r" | grep -o -E '[0-9]+' | head -n 1);
enp5s0_t_irq_pid=$(ps -e | grep "enp5s0-t" | grep -o -E '[0-9]+' | head -n 1);
etherlab_idle_pid=$(ps -e | grep "EtherCAT-IDLE" | grep -o -E '[0-9]+' | head -n 1);
etherlab_op_pid=$(ps -e | grep "EtherCAT-OP" | grep -o -E '[0-9]+' | head -n 1);
ksoftirqd3_pid=$(ps -e | grep "ksoftirqd/3" | grep -o -E '[0-9]+' | head -n 1);
ether_ros_pid=$(ps -e | grep "ether_ros" | grep -o -E '[0-9]+' | head -n 1);
sudo trace-cmd record -p function_graph -e sched:sched_switch -e sched:sched_wakeup -l ecrt_master_send -l ec_master_send_datagrams -l ec_device_send -l ec_gen_netdev_start_xmit -l ec_gen_device_start_xmit -l kernel_sendmsg -l sock_sendmsg -l packet_sendmsg -l dev_queue_xmit -l netdev_pick_tx -l sch_direct_xmit -l dev_hard_start_xmit -l e1000_xmit_frame -l ecrt_master_receive -l ec_device_poll -l ec_gen_poll -l ec_gen_device_poll -l kernel_recvmsg -l sock_recvmsg -l __skb_recv_datagram -l e1000_intr_msi -l __napi_schedule -l __raise_softirq_irqoff -l net_rx_action -l e1000e_poll -l e1000_clean_rx_irq -l napi_gro_receive -l dev_gro_receive -l __netif_receive_skb_core -l sock_queue_rcv_skb -l __sock_queue_rcv_skb -l skb_queue_tail -l schedule -P $enp5s0_irq_pid -P $etherlab_pid -P $ksoftirqd3_pid
sudo trace-cmd record -p function_graph -l ecrt_master_send -l ec_gen_device_start_xmit -l kernel_sendmsg -l dev_hard_start_xmit -l e1000_xmit_frame -l ecrt_master_receive -l ec_gen_device_poll -l kernel_recvmsg -l __skb_recv_datagram -l e1000_intr_msi -l __napi_schedule -l __raise_softirq_irqoff -l net_rx_action -l e1000e_poll -l e1000_clean_rx_irq -l napi_gro_receive -l dev_gro_receive -l __netif_receive_skb_core -l sock_queue_rcv_skb -l __sock_queue_rcv_skb -l skb_queue_tail
9 changes: 9 additions & 0 deletions scripts/trace-cmd/trace_02.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#!/bin/bash
enp5s0_irq_pid=$(ps -e | grep "enp0s25$" | grep -o -E '[0-9]+' | head -n 1);
enp5s0_r_irq_pid=$(ps -e | grep "enp5s0-r" | grep -o -E '[0-9]+' | head -n 1);
enp5s0_t_irq_pid=$(ps -e | grep "enp5s0-t" | grep -o -E '[0-9]+' | head -n 1);
etherlab_idle_pid=$(ps -e | grep "EtherCAT-IDLE" | grep -o -E '[0-9]+' | head -n 1);
etherlab_op_pid=$(ps -e | grep "EtherCAT-OP" | grep -o -E '[0-9]+' | head -n 1);
ksoftirqd3_pid=$(ps -e | grep "ksoftirqd/3" | grep -o -E '[0-9]+' | head -n 1);
ether_ros_pid=$(ps -e | grep "ether_ros" | grep -o -E '[0-9]+' | head -n 1);
sudo trace-cmd record -p function_graph -e sched:sched_switch -e sched:sched_wakeup -l ecrt_master_send -l ec_master_send_datagrams -l ec_device_send -l ec_gen_netdev_start_xmit -l ec_gen_device_start_xmit -l kernel_sendmsg -l sock_sendmsg -l packet_sendmsg -l dev_queue_xmit -l netdev_pick_tx -l sch_direct_xmit -l dev_hard_start_xmit -l e1000_xmit_frame -l ecrt_master_receive -l ec_device_poll -l ec_gen_poll -l ec_gen_device_poll -l kernel_recvmsg -l sock_recvmsg -l __skb_recv_datagram -l e1000_intr_msi -l __napi_schedule -l __raise_softirq_irqoff -l net_rx_action -l e1000e_poll -l e1000_clean_rx_irq -l napi_gro_receive -l dev_gro_receive -l __netif_receive_skb_core -l sock_queue_rcv_skb -l __sock_queue_rcv_skb -l skb_queue_tail -P $enp5s0_irq_pid -P $etherlab_op_pid -P $ksoftirqd3_pid -P $ether_ros_pid
20 changes: 1 addition & 19 deletions src/ether_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,24 +195,6 @@ int main(int argc, char **argv)
process_data_buf = (uint8_t *)malloc(total_process_data * sizeof(uint8_t));
memset(process_data_buf, 0, total_process_data); // fill the buffer with zeros

/******************************************
* Initialize the timing sampling buffers.
*******************************************/
#if TIMING_SAMPLING
statistics_struct stat_struct = {0, 0, 0, 0};
stat_struct.latency_min_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.latency_max_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.period_min_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.period_max_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.exec_min_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.exec_max_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
#elif TIMING_SAMPLING == 0
statistics_struct stat_struct = {0};
stat_struct.latency_ns = (uint32_t *)malloc(RUN_TIME * FREQUENCY * (sizeof(uint32_t)));
stat_struct.period_ns = (uint32_t *)malloc(RUN_TIME * FREQUENCY * (sizeof(uint32_t)));
stat_struct.exec_ns = (uint32_t *)malloc(RUN_TIME * FREQUENCY * (sizeof(uint32_t)));
#endif

n.setParam("/ethercat_slaves/slaves_count", (int)master_info.slave_count); // set the slaves_count to the actual slaves found and configured

//Initialize the Ethercat Communicator and the Ethercat Data Handlers
Expand All @@ -229,7 +211,7 @@ int main(int argc, char **argv)
ros::ServiceServer ethercat_communicatord_service = n.advertiseService("ethercat_communicatord", ethercat_communicatord);
ROS_INFO("Ready to communicate via EtherCAT.");

#ifdef TIMING_SAMPLING
#ifdef LOGGING
/******************************************
* Open Log file *
*******************************************/
Expand Down
62 changes: 47 additions & 15 deletions src/ethercat_communicator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,9 @@ int64_t EthercatCommunicator::system_time_base_ = 0LL;
int EthercatCommunicator::dc_filter_idx_ = 0;
int64_t EthercatCommunicator::dc_adjust_ns_;
#endif
statistics_struct stat_struct;
#ifdef LOGGING
statistics_struct stat_struct;
#endif
//--------------------------------------------------------------------------//

/** Get the time in ns for the current cpu, adjusted by system_time_base_.
Expand Down Expand Up @@ -208,6 +210,27 @@ void EthercatCommunicator::init(ros::NodeHandle &n)
int act_policy;
int ret;

/******************************************
* Initialize the timing sampling buffers.
*******************************************/
#ifdef LOGGING
#ifdef LOGGING_SAMPLING
statistics_struct stat_struct = {0, 0, 0, 0};
stat_struct.latency_min_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.latency_max_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.period_min_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.period_max_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.exec_min_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
stat_struct.exec_max_ns = (uint32_t *)malloc(RUN_TIME * SAMPLING_FREQ * (sizeof(uint32_t)));
#endif
#ifdef LOGGING_NO_SAMPLING
statistics_struct stat_struct = {0};
stat_struct.latency_ns = (uint32_t *)malloc(RUN_TIME * FREQUENCY * (sizeof(uint32_t)));
stat_struct.period_ns = (uint32_t *)malloc(RUN_TIME * FREQUENCY * (sizeof(uint32_t)));
stat_struct.exec_ns = (uint32_t *)malloc(RUN_TIME * FREQUENCY * (sizeof(uint32_t)));
#endif
#endif

if (pthread_attr_init(&current_thattr_))
{
ROS_FATAL("Attribute init\n");
Expand Down Expand Up @@ -307,19 +330,21 @@ void EthercatCommunicator::cleanup_handler(void *arg)
ROS_INFO("Called clean-up handler\n");
}
//--------------------------------------------------------------------------//
#ifdef LOGGING
void EthercatCommunicator::log_statistics_to_file(statistics_struct *ss)
{
int i;
char log_string[100];
#if TIMING_SAMPLING
#ifdef LOGGING_SAMPLING
for (i = 0; i < RUN_TIME * SAMPLING_FREQ; i++)
{
snprintf(log_string, 100, "%10u , %10u , 10u , %10u , 10u , %10u\n",
ss->period_min_ns[i], ss->period_max_ns[i], ss->exec_min_ns[i], ss->exec_max_ns[i],
ss->latency_min_ns[i], ss->latency_max_ns[i]);
dprintf(log_fd, "%s", log_string);
}
#else
#endif
#ifdef LOGGING_NO_SAMPLING
for (i = 0; i < RUN_TIME * FREQUENCY; i++)
{
if (i % 10000 == 0)
Expand All @@ -340,10 +365,12 @@ void EthercatCommunicator::log_statistics_to_file(statistics_struct *ss)
exit(1);
}
}
#endif
//--------------------------------------------------------------------------//
#ifdef LOGGING
void EthercatCommunicator::create_statistics(statistics_struct * ss, struct timespec * wakeup_time_p)
{
#if TIMING_SAMPLING
#ifdef LOGGING_SAMPLING
ss->latency_ns = DIFF_NS(*wakeup_time_p, ss->start_time);
ss->period_ns = DIFF_NS(ss->last_start_time, ss->start_time);
ss->exec_ns = DIFF_NS(ss->last_start_time, ss->end_time);
Expand Down Expand Up @@ -372,24 +399,29 @@ void EthercatCommunicator::create_statistics(statistics_struct * ss, struct time
{
ss->exec_min_ns[ss->statistics_id] = ss->exec_ns;
}
#else
#ifdef LOGGING_NO_SAMPLING
ss->latency_ns[ss->statistics_id] = DIFF_NS(*wakeup_time_p, ss->start_time);
ss->period_ns[ss->statistics_id] = DIFF_NS(ss->last_start_time, ss->start_time);
ss->exec_ns[ss->statistics_id] = DIFF_NS(ss->last_start_time, ss->end_time);
#endif
#endif
}
#endif
//--------------------------------------------------------------------------//
#ifdef LOGGING
void EthercatCommunicator::create_new_statistics_sample(statistics_struct *ss, unsigned int * sampling_counter)
{
#if TIMING_SAMPLING

#ifdef LOGGING_SAMPLING
*sampling_counter = FREQUENCY / SAMPLING_FREQ;
#elif TIMING_SAMPLING == 0
#endif
#ifdef LOGGING_NO_SAMPLING
*sampling_counter = 0;
#endif
ss->statistics_id++;


#if TIMING_SAMPLING
#if defined(LOGGING) && defined(LOGGING_SAMPLING)
// output timing stats
// printf("period %10u ... %10u\n",
// period_min_ns, period_max_ns);
Expand All @@ -406,20 +438,18 @@ void EthercatCommunicator::create_new_statistics_sample(statistics_struct *ss, u
latency_min_ns[ss->statistics_id] = 0xffffffff;
#endif
}
#endif

//--------------------------------------------------------------------------//
void *EthercatCommunicator::run(void *arg)
{
pthread_cleanup_push(EthercatCommunicator::cleanup_handler, NULL);
// #ifdef TIMING_SAMPLING
// struct timespec start_time, end_time, last_start_time = {};
// #endif

unsigned int sampling_counter = 0;
unsigned int sync_ref_counter = 0;
const struct timespec cycletime = {0, PERIOD_NS};
struct timespec break_time, current_time, offset_time = {RUN_TIME, 0}, wakeup_time;
int ret;
// int i = 0;
cpu_set_t cpuset_;
#ifdef DEADLINE_SCHEDULING
struct sched_attr sched_attr_;
Expand Down Expand Up @@ -468,7 +498,7 @@ void *EthercatCommunicator::run(void *arg)
}
wakeup_time = utilities::timespec_add(wakeup_time, cycletime);
clock_nanosleep(CLOCK_TO_USE, TIMER_ABSTIME, &wakeup_time, NULL);
#ifdef TIMING_SAMPLING
#ifdef LOGGING
clock_gettime(CLOCK_TO_USE, & stat_struct.start_time);
create_statistics(&stat_struct, &wakeup_time);
stat_struct.last_start_time = stat_struct.start_time;
Expand All @@ -485,7 +515,9 @@ void *EthercatCommunicator::run(void *arg)
if (!sampling_counter) //if sampling_counter is 0
{
// do this at 10 Hz
#ifdef LOGGING
create_new_statistics_sample(&stat_struct, &sampling_counter);
#endif
// check for master state (optional)
utilities::check_master_state();
}
Expand Down Expand Up @@ -524,13 +556,13 @@ void *EthercatCommunicator::run(void *arg)
{
handle_error_en(ret, "pthread_setcancelstate");
}
#ifdef TIMING_SAMPLING
#ifdef LOGGING
clock_gettime(CLOCK_TO_USE, & stat_struct.end_time);
#endif
clock_gettime(CLOCK_TO_USE, &current_time);
} while (DIFF_NS(current_time, break_time) > 0);

#ifdef TIMING_SAMPLING
#ifdef LOGGING
// write the statistics to file
log_statistics_to_file();
#endif
Expand Down

0 comments on commit 22326db

Please sign in to comment.