Skip to content
Snippets Groups Projects
Commit cc0c7e72 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Merged the version without the motor control library to trunk.

parent e94288f7
No related branches found
No related tags found
No related merge requests found
Showing
with 3548 additions and 2102 deletions
......@@ -11,17 +11,15 @@ FIND_PACKAGE(comm REQUIRED)
FIND_PACKAGE(dynamixel REQUIRED)
FIND_PACKAGE(motor_control REQUIRED)
# edit the following line to add the necessary include directories
INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR} ${comm_INCLUDE_DIR} ${dynamixel_INCLUDE_DIR} ${motor_control_INCLUDE_DIR} .)
INCLUDE_DIRECTORIES(. ${iriutils_INCLUDE_DIR} ${comm_INCLUDE_DIR} ${dynamixel_INCLUDE_DIR})
SET_SOURCE_FILES_PROPERTIES(${XSD_SOURCES} PROPERTIES GENERATED 1)
ADD_LIBRARY(dynamixel_motor_cont SHARED ${sources} ${XSD_SOURCES})
#edit the following line to add the necessary system libraries (if any)
TARGET_LINK_LIBRARIES(dynamixel_motor_cont ${iriutils_LIBRARY} ${comm_LIBRARY} ${dynamixel_LIBRARY} ${motor_control_LIBRARY} ${XSD_LIBRARY})
TARGET_LINK_LIBRARIES(dynamixel_motor_cont ${iriutils_LIBRARY} ${comm_LIBRARY} ${dynamixel_LIBRARY} ${XSD_LIBRARY})
ADD_DEPENDENCIES(dynamixel_motor_cont xsd_files_gen)
......
This diff is collapsed.
#ifndef _DYNAMIXEL_MOTOR_H
#define _DYNAMIXEL_MOTOR_H
#include "dynamixelserver.h"
#include "motor_control.h"
#include "eventserver.h"
#include "ftdimodule.h"
#include "mutex.h"
#include <stdio.h>
#include <stdlib.h>
#include <string>
#include <vector>
typedef enum {
model_number=0x00,
firmware_version=0x02,
id=0x03,
baudrate=0x04,
return_delay_time=0x05,
cw_angle_limit=0x06,
ccw_angle_limit=0x08,
temp_limit=0x0B,
low_voltage_limit=0x0C,
high_voltage_limit=0x0D,
max_torque=0x0E,
return_level=0x10,
alarm_led=0x11,
alarm_shtdwn=0x12,
down_cal=0x14,
up_cal=0x16,
torque_en=0x18,
led=0x19,
pid_p=0x1A,
pid_i=0x1B,
pid_d=0x1C,
cw_comp_margin=0x1A,
ccw_comp_margin=0x1B,
cw_comp_slope=0x1C,
ccw_comp_slope=0x1D,
goal_pos=0x1E,
goal_speed=0x20,
torque_limit=0x22,
current_pos=0x24,
current_speed=0x26,
current_load=0x28,
current_voltage=0x2A,
current_temp=0x2B,
reg_inst=0x2C,
moving=0x2E,
lock=0x2F,
punch=0x30
} reg_id;
typedef enum {
input_voltage_error=0x01,
angle_limit_error=0x02,
overheating_error=0x04,
range_error=0x08,
checksum_error=0x10,
overload_error=0x20,
instruction_error=0x40
}dyn_alarm;
typedef struct
{
std::string model;
unsigned char firmware_ver;
}TDynamixel_info;
typedef struct
{
unsigned char cw_compliance_margin;
unsigned char ccw_compliance_margin;
unsigned char cw_compliance_slope;
unsigned char ccw_compliance_slope;
unsigned char punch;
}TDynamixel_control;
/**
* \brief
*
*/
class CDynamixelMotor : public CMotorControl
{
private:
CDynamixelServer *dyn_server;
/**
* \brief
*
*/
CDynamixel *dynamixel_dev;
/**
* \brief
*
*/
TDynamixel_control control;
/**
* \brief
*
*/
TDynamixel_info info;
/**
* \brief
*
*/
unsigned char alarms;
/**
* \brief
*
*/
bool torque_control;
/**
* \brief
*
*/
long int current_position;
// model attributes
/**
* \brief
*
*/
int dyn_enc_res;
/**
* \brief
*
*/
int dyn_max_angle;
/**
* \brief
*
*/
int dyn_max_speed;
/**
* \brief
*
*/
int dyn_max_torque;
protected:
/**
* \brief
*
*/
virtual void angles_to_controller(std::vector<float>& angles,std::vector<float>& counts);
/**
* \brief
*
*/
virtual void speeds_to_controller(std::vector<float>& angles,std::vector<float>& counts);
/**
* \brief
*
*/
virtual void accels_to_controller(std::vector<float>& angles,std::vector<float>& counts);
/**
* \brief
*
*/
virtual void controller_to_angles(std::vector<float>& counts,std::vector<float>& angles);
/**
* \brief
*
*/
virtual void controller_to_speeds(std::vector<float>& counts,std::vector<float>& angles);
/**
* \brief
*
*/
virtual void controller_to_accels(std::vector<float>& counts,std::vector<float>& angles);
/**
* \brief
*
*/
virtual void cont_set_position_range(std::vector<float>& min, std::vector<float>& max);
/**
* \brief
*
*/
virtual void cont_get_position_range(std::vector<float>& min, std::vector<float>& max);
/**
* \brief
*
*/
virtual void cont_get_gear_factor(std::vector<float>& gear);
/**
* \brief
*
*/
virtual std::vector<float> cont_get_position(void);
/**
* \brief
*
*/
virtual std::vector<float> cont_get_velocity(void);
/**
* \brief
*
*/
virtual void cont_enable(std::vector<bool> &enable);
/**
* \brief
*
*/
virtual void cont_disable(std::vector<bool> &disable);
/**
* \brief
*
*/
virtual void cont_load(std::vector<float>& position, std::vector<float>& velocity, std::vector<float>& accel);
/**
* \brief
*
*/
virtual void cont_load(std::vector<float>& velocity, std::vector<float>& accel);
/**
* \brief
*
*/
virtual void cont_move(void);
/**
* \brief
*
*/
virtual void cont_stop(void);
/**
* \brief
*
*/
virtual void cont_close(void);
#ifdef _HAVE_XSD
/**
* \brief
*
*/
virtual void cont_load_config(std::string &filename);
/**
* \brief
*
*/
virtual void cont_save_config(std::string &filename);
#endif
/**
* \brief
*
*/
void reset_motor(void);
public:
/**
* \brief
*
*/
CDynamixelMotor(std::string& cont_id,unsigned char bus_id,int baudrate,unsigned char dev_id);
/**
* \brief
*
*/
CDynamixelMotor(std::string& cont_id,std::string &bus_id,int baudrate,unsigned char dev_id);
/**
* \brief
*
*/
int get_baudrate(void);
/**
* \brief
*
*/
unsigned char get_node_address(void);
/**
* \brief
*
*/
void set_node_address(unsigned char dev_id);
/**
* \brief
*
*/
std::string get_model(void);
/**
* \brief
*
*/
int get_id(void);
/**
* \brief
*
*/
unsigned char get_firmware_version(void);
/**
* \brief
*
*/
int get_temperature_limit(void);
/**
* \brief
*
*/
void set_temperature_limit(int limit);
/**
* \brief
*
*/
int get_current_temperature(void);
/**
* \brief
*
*/
void get_voltage_limits(float *min, float *max);
/**
* \brief
*
*/
void set_voltage_limits(float min, float max);
/**
* \brief
*
*/
float get_current_voltage(void);
/**
* \brief
*
*/
unsigned char get_led_alarms(void);
/**
* \brief
*
*/
void set_led_alarms(unsigned char alarms);
/**
* \brief
*
*/
unsigned char get_turn_off_alarms(void);
/**
* \brief
*
*/
void set_turn_off_alarms(unsigned char alarms);
/**
* \brief
*
*/
void turn_led_on(void);
/**
* \brief
*
*/
void turn_led_off(void);
/**
* \brief
*
*/
void get_compliance_margin(unsigned char *cw_margin, unsigned char *ccw_margin);
/**
* \brief
*
*/
void set_compliance_margin(unsigned char cw_margin, unsigned char ccw_margin);
/**
* \brief
*
*/
void get_compliance_slope(unsigned char *cw_slope, unsigned char *ccw_margin);
/**
* \brief
*
*/
void set_compliance_slope(unsigned char cw_slope, unsigned char ccw_slope);
/**
* \brief
*
*/
short int get_punch(void);
/**
* \brief
*
*/
void set_punch(short int punch_value);
/**
* \brief
*
*/
void get_pid(unsigned char *p,unsigned char *i,unsigned char *d);
/**
* \brief
*
*/
void set_pid(unsigned char p,unsigned char i,unsigned char d);
/**
* \brief
*
*/
bool is_locked(void);
/**
* \brief
*
*/
void lock(void);
/**
* \brief
*
*/
void enable_torque_control(void);
/**
* \brief
*
*/
void disable_torque_control(void);
/**
* \brief
*
*/
bool is_torque_control_enabled(void);
/**
* \brief
*
*/
void set_torque(float torque_ratio);
/**
* \brief
*
*/
float get_torque(void);
/**
* \brief
*
*/
float get_max_torque(void);
/**
* \brief
*
*/
float get_limit_torque(void);
/**
* \brief
*
*/
virtual ~CDynamixelMotor();
};
#endif
#ifndef _DYNAMIXEL_MOTOR_H
#define _DYNAMIXEL_MOTOR_H
#include "dynamixelserver.h"
#include "threadserver.h"
#include "eventserver.h"
#include "ftdimodule.h"
#include "mutex.h"
#include <stdio.h>
#include <stdlib.h>
#include <string>
#include <vector>
#include <memory>
typedef enum {
// [Access] [Description]
// EEPROM Area
model_number=0x00, // (R) Model Number
firmware_version=0x02, // (R) Version of the Firmware
id=0x03, // (RW) ID of Dynamixel
baudrate=0x04, // (RW) Baud Rate of Dynamixel
return_delay_time=0x05, // (RW) Return Delay Time
cw_angle_limit=0x06, // (RW) Clockwise Angle Limit
ccw_angle_limit=0x08, // (RW) Counterclockwise Angle Limit
temp_limit=0x0B, // (RW) Internal Temperature Limit
low_voltage_limit=0x0C, // (RW) Lowest Voltage Limit
high_voltage_limit=0x0D, // (RW) Highest Voltage Limit
max_torque=0x0E, // (RW) Maximum Torque
return_level=0x10, // (RW) Status Return Level
alarm_led=0x11, // (RW) LED for Alarm
alarm_shtdwn=0x12, // (RW) Shutdown for Alarm
down_cal=0x14, // (RW)
up_cal=0x16, // (RW)
// RAM Area
torque_en=0x18, // (RW) Torque On/Off
led=0x19, // (RW) LED On/Off
pid_p=0x1A, // (RW)
pid_i=0x1B, // (RW)
pid_d=0x1C, // (RW)
cw_comp_margin=0x1A, // (RW) CW Compliance Margin
ccw_comp_margin=0x1B, // (RW) CCW Compliance Margin
cw_comp_slope=0x1C, // (RW) CW Compliance Slope
ccw_comp_slope=0x1D, // (RW) CCW Compliance Slope
goal_pos=0x1E, // (RW) Goal Position
goal_speed=0x20, // (RW) Moving Speed
torque_limit=0x22, // (RW) Torque Limit
current_pos=0x24, // (R) Current Position
current_speed=0x26, // (R) Current Speed
current_load=0x28, // (R) Current Load
current_voltage=0x2A, // (R) Current Voltage
current_temp=0x2B, // (RW) Current Temperature
reg_inst=0x2C, // (RW) Means if Instruction is registered
moving=0x2E, // (R) Means if there is any movement
lock=0x2F, // (RW) Locking EEPROM
punch=0x30 // (RW) Punch
} reg_id;
typedef enum
{
input_voltage_error=0x01,
angle_limit_error=0x02,
overheating_error=0x04,
range_error=0x08,
checksum_error=0x10,
overload_error=0x20,
instruction_error=0x40
}dyn_alarm;
typedef struct
{
std::string model;
unsigned char firmware_ver;
unsigned int gear_ratio;
unsigned int encoder_resolution;
bool pid_control;
double max_angle;
double center_angle;
double max_speed;
std::string bus_id;
unsigned int baudrate;
unsigned char id;
}TDynamixel_info;
typedef struct
{
unsigned char cw_compliance_margin;
unsigned char ccw_compliance_margin;
unsigned char cw_compliance_slope;
unsigned char ccw_compliance_slope;
unsigned char punch;
}TDynamixel_compliance;
typedef struct
{
unsigned char p;
unsigned char i;
unsigned char d;
}TDynamixel_pid;
typedef struct
{
double max_angle;
double min_angle;
double max_temperature;
double max_voltage;
double min_voltage;
double max_torque;
}TDynamixel_config;
typedef enum{angle_ctrl=0,torque_ctrl=1} control_mode;
/**
* \brief
*
*/
class CDynamixelMotor
{
private:
CDynamixelServer *dyn_server;
/**
* \brief
*
*/
CDynamixel *dynamixel_dev;
/**
* \brief
*
*/
TDynamixel_compliance compliance;
/**
* \brief
*
*/
TDynamixel_pid pid;
/**
* \brief
*
*/
TDynamixel_config config;
/**
* \brief
*
*/
TDynamixel_info info;
/**
* \brief
*
*/
unsigned char alarms;
/**
* \brief
*
*/
control_mode mode;
protected:
/**
* \brief
*
*/
unsigned int from_angles(double angle);
/**
* \brief
*
*/
unsigned int from_speeds(double speed);
/**
* \brief
*
*/
double to_angles(unsigned short int counts);
/**
* \brief
*
*/
double to_speeds(unsigned short int counts);
/**
* \brief
*
*/
void reset_motor(void);
/**
* \brief
*
*/
void get_model(void);
public:
/**
* \brief
*
*/
CDynamixelMotor(std::string& cont_id,unsigned char bus_id,int baudrate,unsigned char dev_id);
/**
* \brief
*
*/
CDynamixelMotor(std::string& cont_id,std::string &bus_id,int baudrate,unsigned char dev_id);
/**
* \brief
*
*/
void get_servo_info(TDynamixel_info &info);
/* configuration functions */
/**
* \brief
*
*/
void load_config(TDynamixel_config &config);
#ifdef _HAVE_XSD
/**
* \brief
*
*/
void load_config(std::string &filename);
/**
* \brief
*
*/
void save_config(std::string &filename);
#endif
/**
* \brief
*
*/
void set_position_range(double min,double max);
/**
* \brief
*
*/
void get_position_range(double *min, double *max);
/**
* \brief
*
*/
int get_temperature_limit(void);
/**
* \brief
*
*/
void set_temperature_limit(int limit);
/**
* \brief
*
*/
void get_voltage_limits(double *min, double *max);
/**
* \brief
*
*/
void set_voltage_limits(double min, double max);
/**
* \brief
*
*/
unsigned char get_led_alarms(void);
/**
* \brief
*
*/
void set_led_alarms(unsigned char alarms);
/**
* \brief
*
*/
unsigned char get_turn_off_alarms(void);
/**
* \brief
*
*/
void set_turn_off_alarms(unsigned char alarms);
/**
* \brief
*
*/
double get_max_torque(void);
/**
* \brief
*
*/
double get_limit_torque(void);
/**
* \brief
*
*/
void set_max_torque(double torque_ratio);
/**
* \brief
*
*/
void set_limit_torque(double torque_ratio);
/**
* \brief
*
*/
void get_compliance_control(TDynamixel_compliance &config);
/**
* \brief
*
*/
void set_compliance_control(TDynamixel_compliance &config);
/**
* \brief
*
*/
void get_pid_control(TDynamixel_pid &config);
/**
* \brief
*
*/
void set_pid_control(TDynamixel_pid &config);
/* control functions */
/**
* \brief
*
*/
void turn_led_on(void);
/**
* \brief
*
*/
void turn_led_off(void);
/**
* \brief
*
*/
bool is_locked(void);
/**
* \brief
*
*/
void lock(void);
/**
* \brief
*
*/
void enable(void);
/**
* \brief
*
*/
void disable(void);
/**
* \brief
*
*/
void move_absolute_angle(double angle,double speed);
/**
* \brief
*
*/
void move_relative_angle(double angle,double speed);
/**
* \brief
*
*/
void move_torque(double torque_ratio);
/**
* \brief
*
*/
void stop(void);
/**
* \brief
*
*/
double get_current_angle(void);
/**
* \brief
*
*/
double get_current_speed(void);
/**
* \brief
*
*/
double get_current_effort(void);
/**
* \brief
*
*/
double get_current_voltage(void);
/**
* \brief
*
*/
double get_current_temperature(void);
/**
* \brief
*
*/
virtual ~CDynamixelMotor();
};
#endif
......@@ -5,6 +5,7 @@
const std::string dynamixel_motor_error_message="DynamixelMotor error - ";
const std::string dynamixel_motor_group_error_message="DynamixelMotorGroup error - ";
const std::string dynamixel_motion_sequence_error_message="DynamixelMotionSeq error - ";
CDynamixelMotorException::CDynamixelMotorException(const std::string& where,const std::string &error_msg):CException(where,dynamixel_motor_error_message)
{
......@@ -20,3 +21,9 @@ CDynamixelMotorGroupException::CDynamixelMotorGroupException(const std::string&
this->error_msg+=error_msg;
}
CDynamixelMotionSequenceException::CDynamixelMotionSequenceException(const std::string& where,const std::string &error_msg):CException(where,dynamixel_motion_sequence_error_message)
{
std::stringstream text;
this->error_msg+=error_msg;
}
......@@ -33,4 +33,16 @@ class CDynamixelMotorGroupException : public CException
CDynamixelMotorGroupException(const std::string& where,const std::string &error_msg);
};
/**
* \brief
*/
class CDynamixelMotionSequenceException : public CException
{
public:
/**
* \brief
*
*/
CDynamixelMotionSequenceException(const std::string& where,const std::string &error_msg);
};
#endif
This diff is collapsed.
This diff is collapsed.
......@@ -2,40 +2,16 @@
ADD_EXECUTABLE(test_dynamixel_motor test_dynamixel_motor.cpp)
# edit the following line to add the necessary libraries
TARGET_LINK_LIBRARIES(test_dynamixel_motor dynamixel_motor_cont ${comm_LIBRARY} ${motor_control_LIBRARY})
# edit the following line to add the source code for the example and the name of the executable
ADD_EXECUTABLE(test_dynamixel_motor_scan test_dynamixel_motor_scan.cpp)
# edit the following line to add the necessary libraries
TARGET_LINK_LIBRARIES(test_dynamixel_motor_scan dynamixel_motor_cont ${comm_LIBRARY} ${motor_control_LIBRARY})
# edit the following line to add the source code for the example and the name of the executable
ADD_EXECUTABLE(test_sequence test_sequence.cpp)
# edit the following line to add the necessary libraries
TARGET_LINK_LIBRARIES(test_sequence dynamixel_motor_cont ${comm_LIBRARY} ${motor_control_LIBRARY})
TARGET_LINK_LIBRARIES(test_dynamixel_motor dynamixel_motor_cont ${comm_LIBRARY})
# edit the following line to add the source code for the example and the name of the executable
ADD_EXECUTABLE(test_dynamixel_motor_group test_dynamixel_motor_group.cpp)
# edit the following line to add the necessary libraries
TARGET_LINK_LIBRARIES(test_dynamixel_motor_group dynamixel_motor_cont ${comm_LIBRARY} ${motor_control_LIBRARY})
# edit the following line to add the source code for the example and the name of the executable
ADD_EXECUTABLE(test_dynamixel_motor_open_loop test_dynamixel_motor_open_loop.cpp)
# edit the following line to add the necessary libraries
TARGET_LINK_LIBRARIES(test_dynamixel_motor_open_loop dynamixel_motor_cont ${comm_LIBRARY} ${motor_control_LIBRARY})
# edit the following line to add the source code for the example and the name of the executable
ADD_EXECUTABLE(test_dynamixel_motor_group_open_loop test_dynamixel_motor_group_open_loop.cpp)
# edit the following line to add the necessary libraries
TARGET_LINK_LIBRARIES(test_dynamixel_motor_group_open_loop dynamixel_motor_cont ${comm_LIBRARY} ${motor_control_LIBRARY})
TARGET_LINK_LIBRARIES(test_dynamixel_motor_group dynamixel_motor_cont ${comm_LIBRARY})
# edit the following line to add the source code for the example and the name of the executable
ADD_EXECUTABLE(test_sequence_open_loop test_sequence_open_loop.cpp)
ADD_EXECUTABLE(test_dynamixel_motion_seq test_dynamixel_motion_seq.cpp)
# edit the following line to add the necessary libraries
TARGET_LINK_LIBRARIES(test_sequence_open_loop dynamixel_motor_cont ${comm_LIBRARY} ${motor_control_LIBRARY})
TARGET_LINK_LIBRARIES(test_dynamixel_motion_seq dynamixel_motor_cont ${comm_LIBRARY})
#include "dynamixelexceptions.h"
#include "dynamixelserver.h"
#include "eventserver.h"
#include "exceptions.h"
#include "dynamixel_motor_group.h"
#include "dynamixel_motor.h"
#include <iostream>
#include <math.h>
std::string sequence_filename="../src/xml/sequence1.xml";
std::string group_name="GROUP1";
std::string config_file="../src/xml/dyn_group_config.xml";
int main(int argc, char *argv[])
{
CDynamixelServer *dyn_server=CDynamixelServer::instance();
CEventServer *event_server=CEventServer::instance();
std::vector<double> angles,speeds;
CDynamixelMotorGroup group(group_name);
try{
if(dyn_server->get_num_buses()>0)
{
group.load_config(config_file);
group.load_sequence(sequence_filename);
group.start_sequence();
while(!event_server->event_is_set(group.get_sequence_complete_event_id()))
{
std::cout << group.get_sequence_completed_percentage() << "% of sequence completed" << std::endl;
usleep(200000);
}
}
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -13,7 +13,7 @@ ENDIF(EXISTS "/usr/include/xsd/cxx")
IF(XSD_FOUND)
SET(XSD_LIBRARY ${XSD_LIBRARY} PARENT_SCOPE)
SET(XSD_FILES dynamixel_motor_cfg_file.xsd)
SET(XSD_FILES dynamixel_motor_cfg_file.xsd dynamixel_motor_group_cfg_file.xsd dyn_motion_seq_file.xsd)
IF(XSD_FILES)
SET(XSD_PATH ${CMAKE_CURRENT_SOURCE_DIR})
......@@ -34,7 +34,7 @@ IF(XSD_FOUND)
ADD_CUSTOM_TARGET(xsd_files_gen DEPENDS ${XSD_SOURCES_INT})
ADD_CUSTOM_COMMAND(
OUTPUT ${XSD_SOURCES_INT}
COMMAND xsd cxx-tree --generate-serialization ${XSD_FILES}
COMMAND xsdcxx cxx-tree --generate-serialization ${XSD_FILES}
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
DEPENDS ${XSD_PATH_FILES}
COMMENT "Parsing the xml template file ${XSD_FILES}")
......
This diff is collapsed.
......@@ -3,12 +3,19 @@
<dynamixel_motor_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:noNamespaceSchemaLocation="dynamixel_motor_cfg_file.xsd">
<alarm_shtdwn>4</alarm_shtdwn>
<min_angle>-125</min_angle>
<max_angle>125</max_angle>
<temp_limit>85</temp_limit>
<max_voltage>19</max_voltage>
<min_voltage>6</min_voltage>
<cw_comp_margin>2</cw_comp_margin>
<ccw_comp_margin>2</ccw_comp_margin>
<cw_comp_slope>16</cw_comp_slope>
<ccw_comp_slope>16</ccw_comp_slope>
<punch>0</punch>
<max_torque>100</max_torque>
<cw_comp_margin>0</cw_comp_margin>
<ccw_comp_margin>0</ccw_comp_margin>
<cw_comp_slope>32</cw_comp_slope>
<ccw_comp_slope>32</ccw_comp_slope>
<punch>32</punch>
<kp>0</kp>
<ki>0</ki>
<kd>0</kd>
</dynamixel_motor_config>
This diff is collapsed.
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment