Defines | Functions | Variables
this_node.c File Reference
#include "this_node.h"
#include "tests/assert_shadow.h"
#include "internal_reporting/internal_reporting.h"
#include "hardware/et1200/et1200_interface.h"
#include <peripheral/spi.h>
Include dependency graph for this_node.c:

Go to the source code of this file.

Defines

#define CORE_TIMER_TO_MICROSECONDS(x)   ((x) / (SYSTEM_FREQ_HZ/2000000))
 Convert from the number of core ticks returned by ReadCoreTimer to a real time in microseconds.

Functions

void __assert_dynamic_fail (const char *UNUSED(fmt),...)
void approx_1ms_handler (void)
int16u calculate_idle_time (void)
void Check_For_EtherCAT_Packet (void)
void delay_ms (int32u milliseconds)
void delay_us (int32u microseconds)
int32u get_frame_time_us (void)
void initialise_this_node (void)
int8u not_all_motor_data_received (void)
void Platform_Init_Callback (void)
void Read_All_Sensors (void)
void Read_Commands_From_ET1200 (void)
void Received_Motor_Data (FROM_MOTOR_DATA_TYPE data_type, int8u motor_number, int16s measured_torque, int16u other_value)
void report_error_code (ERROR_CODE error_code)
void report_error_string (char *error_string,...)
void report_event_code (EVENT_CODE event_code)
void report_event_string (char *event_string,...)
int8u ROS_Wants_me_to_send_CAN (void)
void run_tests (void)
void Service_EtherCAT_Packet (void)
int8u There_is_Command_From_ET1200 (void)
void Wait_For_All_Motors_To_Send_Data (int32u timeout_us)
void Wait_For_Until_Frame_Time (int32u frame_time_us)
void write_status_data_To_ET1200 (void)
void zero_motor_data_packets (void)

Variables

ETHERCAT_CAN_BRIDGE_DATA can_bridge_data_from_ROS
ETHERCAT_CAN_BRIDGE_DATA can_bridge_data_to_ROS
LED_Class * ET1200_AL_err_LED
 EtherCAT Application Layer Error LED. See EtherCAT Indicator Specification V0.91.pdf section 4.5 ERR Indicator.
ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND etherCAT_command_data
 Data structure containing command data, arrived from host PC.
ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS etherCAT_status_data
 Data structure containing sensor data, going to PC.
int32u frame_start_time = 0
 Is set to the value of the MIPS core timer when an EtherCAT packet arrives.
int32u global_AL_Event_Register = 0
int32u idle_time_start = 0
 Is set to the value of the MIPS core timer when the status data are written to the ET1200.
LED_Class * LED_CAN1_ERR
 The CAN 1 error LED.
LED_Class * LED_CAN1_RX
 The CAN 1 receive LED.
LED_Class * LED_CAN1_TX
 The CAN 1 transmit LED.
LED_Class * LED_CAN2_ERR
 The CAN 2 error LED.
LED_Class * LED_CAN2_RX
LED_Class * LED_CAN2_TX
 The CAN 2 transmit LED.
int64u node_id = 0
 Which group this documentation should go in.
int num_motor_CAN_messages_received_this_frame = 0
 Count of the number of CAN messages received since the Start Of Frame message was sent.
int8u palm_EDC_0200_sensor_mapping [64]
TACTILE_SENSOR_PROTOCOL_TYPE tactile_sensor_protocol = TACTILE_SENSOR_PROTOCOL_TYPE_INVALID

Detailed Description

Definition in file this_node.c.


Define Documentation

#define CORE_TIMER_TO_MICROSECONDS (   x)    ((x) / (SYSTEM_FREQ_HZ/2000000))

Convert from the number of core ticks returned by ReadCoreTimer to a real time in microseconds.

Definition at line 56 of file this_node.c.


Function Documentation

void __assert_dynamic_fail ( const char *  UNUSEDfmt,
  ... 
)

Flash all the lights like crazy to show that there has been an assert failure.

Author:
Hugo Elias

Definition at line 739 of file this_node.c.

void approx_1ms_handler ( void  )

This function should be called about once every millisecond. It can either be called once for every EtherCAT packet, or just based on a timer. If this function isn't called, then the Watch Dog timer will time out.

Author:
Hugo Elias

Definition at line 136 of file this_node.c.

Idle time is the time the PIC spends waiting for the next EtherCAT packet to arrive. The timer is started when the Status data has been completely written to the ET1200, and stopped as soon as the PIC knows that new Command data are available.

Author:
Hugo Elias

Definition at line 383 of file this_node.c.

void Check_For_EtherCAT_Packet ( void  )

Ask the ET1200 if an EtherCAT packet arrived. If so, get it serviced. Also, handle the LEDs etc if they need doing.

Author:
Hugo Elias

Definition at line 514 of file this_node.c.

void delay_ms ( int32u  milliseconds)

Correct length pause, which works by watching the CP0 COUNT register. This code handles one rollover, so, as long as the delay isn't more than 107 seconds, you should be OK.

Parameters:
millisecondsThe number of microseconds to pause for
Author:
Hugo Elias

Definition at line 825 of file this_node.c.

void delay_us ( int32u  microseconds)

Correct length pause, which works by watching the CP0 COUNT register.

Parameters:
microsecondsThe number of microseconds to pause for
Author:
Hugo Elias

Definition at line 805 of file this_node.c.

Return the time in microseconds since the the beginning of the current 1ms frame. The timer is started when the PIC sees that new Command data are available.

Author:
Hugo Elias

Definition at line 326 of file this_node.c.

void initialise_this_node ( void  )

Initialise the hardware of this node. I/O pins SPI I2C LEDs ET1200 interface ET1200 CAN buses parallel SPI tactile sensors

Author:
Hugo Elias

Definition at line 162 of file this_node.c.

Are we still waiting for CAN messages to arrive?

Author:
Hugo Elias

Definition at line 315 of file this_node.c.

void Platform_Init_Callback ( void  )

Called when entering the Init state

Author:
Hugo Elias (based on code by Rich Walker)

Definition at line 624 of file this_node.c.

void Read_All_Sensors ( void  )

Read all of the Joint and Tactile sensors on the Palm

Author:
Hugo Elias

Definition at line 394 of file this_node.c.

void Read_Commands_From_ET1200 ( void  )

Definition at line 261 of file this_node.c.

void Received_Motor_Data ( FROM_MOTOR_DATA_TYPE  data_type,
int8u  motor_number,
int16s  measured_torque,
int16u  other_value 
)

Called when a CAN message arrives from motor unit, containing measured torque, and one other value. Declared in simple_can.h

Parameters:
data_typeTells us the meaning of other_value.
motor_IDWhich motor did this message come from? range[0..19].
measured_torqueWhat is says.
other_valueAnother value, the meaning of which is determined by data_type.
Author:
Hugo Elias

Definition at line 771 of file this_node.c.

void report_error_code ( ERROR_CODE  error_code)

Catch error codes generated by other functions. Report those errors to the user. Currently only handles CAN bus errors, which are reported by flickering the red LED for that bus.

Parameters:
error_codean error code as defined in this_node.h
Author:
Hugo Elias

Definition at line 647 of file this_node.c.

void report_error_string ( char *  error_string,
  ... 
)

Currently unimplemented. Will cause assert failure if called.

Author:
Hugo Elias

Definition at line 716 of file this_node.c.

void report_event_code ( EVENT_CODE  event_code)

Catch event codes generated by other functions. Report those events to the user. Currently only handles CAN bus events, which are reported by flickering the blue LEDs for that bus.

Parameters:
event_codean event code as defined in this_node.h
Author:
Hugo Elias

Definition at line 682 of file this_node.c.

void report_event_string ( char *  event_string,
  ... 
)

Currently unimplemented, but safe to call.

Author:
Hugo Elias

Definition at line 728 of file this_node.c.

Here we check the content of AL Event Register (0x220) We check the bit 9, which is "SyncManager1 interrupt pending" SyncManager0 is the Command SyncManager. See II-36 of the ET1200 datasheet. This function DOES NOT read the Global AL Event register (0x220). It assumes the register has already been read

Author:
Yann Sionneau

Definition at line 305 of file this_node.c.

void run_tests ( void  )

Definition at line 122 of file this_node.c.

void Service_EtherCAT_Packet ( void  )

This is the main function of the whole node. It's called every time an EtherCAT packet arrives.

Author:
Hugo Elias

Definition at line 550 of file this_node.c.

Here we check the content of AL Event Register (0x220) We check the bit 8, which is "SyncManager0 interrupt pending" SyncManager0 is the Command SyncManager. See II-36 of the ET1200 datasheet. This function reads the Global AL Event register (0x220).

Author:
Yann Sionneau

Definition at line 290 of file this_node.c.

Half the motors will each send back one data message. Wait until we have 5 messages from each bus, then we can write the data back to the ET1200

But, at some point, we have to time out, because either some motors aren't there, or they're just late.

Parameters:
timeout_usHow long, in microseconds, after the start of frame should we give up waiting?
Author:
Hugo Elias

Definition at line 343 of file this_node.c.

void Wait_For_Until_Frame_Time ( int32u  frame_time_us)

Wait until a certain time within the 1000us frame time. This is a useful function for waiting until the last moment to see if any more CAN messages arrive, before writing data back to the ET1200.

Frame time is in microseconds, starting at 0 when the EtherCAT packet arrives, and should never be seen to go beyond 1000, when the next EtherCAT packet should arrive.

Parameters:
frame_time_usThe frame time in microseconds.
Author:
Hugo Elias

Definition at line 369 of file this_node.c.

void write_status_data_To_ET1200 ( void  ) [inline]

Write the whole etherCAT_status_data[] array to the ET1200. Once these data are written, we are ready for the next EtherCAT packet to arrive, and the idle timer starts.

Author:
Hugo Elias

Definition at line 277 of file this_node.c.

void zero_motor_data_packets ( void  )

Zero the array containing the motor data so that it's tidy.

Author:
Hugo Elias

Definition at line 493 of file this_node.c.


Variable Documentation

ETHERCAT_CAN_BRIDGE_DATA can_bridge_data_from_ROS

Definition at line 52 of file this_node.c.

ETHERCAT_CAN_BRIDGE_DATA can_bridge_data_to_ROS

Definition at line 53 of file this_node.c.

LED_Class* ET1200_AL_err_LED

EtherCAT Application Layer Error LED. See EtherCAT Indicator Specification V0.91.pdf section 4.5 ERR Indicator.

Definition at line 101 of file this_node.c.

ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND etherCAT_command_data

Data structure containing command data, arrived from host PC.

Definition at line 49 of file this_node.c.

ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS etherCAT_status_data

Data structure containing sensor data, going to PC.

Definition at line 50 of file this_node.c.

Is set to the value of the MIPS core timer when an EtherCAT packet arrives.

Definition at line 88 of file this_node.c.

Definition at line 45 of file this_node.c.

Is set to the value of the MIPS core timer when the status data are written to the ET1200.

Definition at line 89 of file this_node.c.

LED_Class* LED_CAN1_ERR

The CAN 1 error LED.

Definition at line 96 of file this_node.c.

LED_Class* LED_CAN1_RX

The CAN 1 receive LED.

Definition at line 95 of file this_node.c.

LED_Class* LED_CAN1_TX

The CAN 1 transmit LED.

Definition at line 94 of file this_node.c.

LED_Class* LED_CAN2_ERR

The CAN 2 error LED.

Definition at line 99 of file this_node.c.

LED_Class* LED_CAN2_RX

This LED is optional, and exists if LED_CAN2_RX_PIN is defined. It's the CAN 2 receive LED. If it's not defined, then LED_CFG probably is.

Definition at line 112 of file this_node.c.

LED_Class* LED_CAN2_TX

The CAN 2 transmit LED.

Definition at line 98 of file this_node.c.

Which group this documentation should go in.

Definition at line 44 of file this_node.c.

Count of the number of CAN messages received since the Start Of Frame message was sent.

Definition at line 118 of file this_node.c.

Definition at line 47 of file this_node.c.



sr_external_dependencies
Author(s): Ugo Cupcic/ ugo@shadowrobot.com, software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:01:42