|
From: <rob...@us...> - 2008-10-30 01:15:54
|
Revision: 5981
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5981&view=rev
Author: rob_wheeler
Date: 2008-10-30 01:15:50 +0000 (Thu, 30 Oct 2008)
Log Message:
-----------
Support updated MCB firmware which fixes a bug in the calibration sensor reading.
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h
pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2008-10-30 01:09:28 UTC (rev 5980)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2008-10-30 01:15:50 UTC (rev 5981)
@@ -111,7 +111,7 @@
break;
case BEGINNING:
original_switch_state_ = actuator_->state_.calibration_reading_;
- cc_.steer_velocity_ = (original_switch_state_ ? search_velocity_ : -search_velocity_);
+ cc_.steer_velocity_ = (original_switch_state_ ? -search_velocity_ : search_velocity_);
state_ = MOVING;
break;
case MOVING: {
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp 2008-10-30 01:09:28 UTC (rev 5980)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp 2008-10-30 01:15:50 UTC (rev 5981)
@@ -123,7 +123,7 @@
break;
case BEGINNING:
original_switch_state_ = actuator_->state_.calibration_reading_;
- vc_.setCommand(original_switch_state_ ? search_velocity_ : -search_velocity_);
+ vc_.setCommand(original_switch_state_ ? -search_velocity_ : search_velocity_);
state_ = MOVING;
break;
case MOVING: {
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2008-10-30 01:09:28 UTC (rev 5980)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2008-10-30 01:15:50 UTC (rev 5981)
@@ -174,8 +174,8 @@
uint16_t num_encoder_errors_;
uint8_t encoder_status_;
uint8_t calibration_reading_;
+ int32_t last_calibration_rising_edge_;
int32_t last_calibration_falling_edge_;
- int32_t last_calibration_rising_edge_;
uint16_t board_temperature_;
uint16_t bridge_temperature_;
uint16_t supply_voltage_;
@@ -256,8 +256,10 @@
enum
{
- LIMIT_SENSOR_0_STATE = 1, LIMIT_SENSOR_1_STATE = 2,
- LIMIT_OFF_TO_ON = 4, LIMIT_ON_TO_OFF = 8
+ LIMIT_SENSOR_0_STATE = (1 << 0),
+ LIMIT_SENSOR_1_STATE = (1 << 1),
+ LIMIT_ON_TO_OFF = (1 << 2),
+ LIMIT_OFF_TO_ON = (1 << 3)
};
enum
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-30 01:09:28 UTC (rev 5980)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-30 01:15:50 UTC (rev 5981)
@@ -199,7 +199,7 @@
if (sh_->get_product_code() == WG05::PRODUCT_CODE)
{
- if (major != 1 || minor < 6)
+ if (major != 1 || minor != 7)
{
ROS_FATAL("Unsupported firmware revision %d.%02d\n", major, minor);
ROS_BREAK();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|