|
From: <rob...@us...> - 2008-10-20 19:51:51
|
Revision: 5560
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5560&view=rev
Author: rob_wheeler
Date: 2008-10-20 19:51:45 +0000 (Mon, 20 Oct 2008)
Log Message:
-----------
- Add flags to indicate if the last calibration settings are valid.
- Correct the sense of rising and falling edges of the calibration sensor
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
pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h
pkg/trunk/mechanism/mechanism_control/scripts/listen.py
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/robot_msgs/msg/ActuatorState.msg
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-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2008-10-20 19:51:45 UTC (rev 5560)
@@ -110,12 +110,12 @@
state_ = BEGINNING;
break;
case BEGINNING:
- original_switch_state_ = actuator_->state_.calibration_reading_ > 0.5;
+ original_switch_state_ = actuator_->state_.calibration_reading_;
cc_.steer_velocity_ = (original_switch_state_ ? search_velocity_ : -search_velocity_);
state_ = MOVING;
break;
case MOVING: {
- bool switch_state_ = actuator_->state_.calibration_reading_ > 0.5;
+ bool switch_state_ = actuator_->state_.calibration_reading_;
if (switch_state_ != original_switch_state_)
{
Actuator a;
@@ -126,7 +126,7 @@
fake_j.push_back(&j);
// Where was the joint when the optical switch triggered?
- if (original_switch_state_ == true)
+ if (switch_state_ == true)
fake_a[0]->state_.position_ = actuator_->state_.last_calibration_rising_edge_;
else
fake_a[0]->state_.position_ = actuator_->state_.last_calibration_falling_edge_;
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-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp 2008-10-20 19:51:45 UTC (rev 5560)
@@ -122,12 +122,12 @@
state_ = BEGINNING;
break;
case BEGINNING:
- original_switch_state_ = actuator_->state_.calibration_reading_ > 0.5;
+ original_switch_state_ = actuator_->state_.calibration_reading_;
vc_.setCommand(original_switch_state_ ? search_velocity_ : -search_velocity_);
state_ = MOVING;
break;
case MOVING: {
- bool switch_state_ = actuator_->state_.calibration_reading_ > 0.5;
+ bool switch_state_ = actuator_->state_.calibration_reading_;
if (switch_state_ != original_switch_state_)
{
Actuator a;
@@ -138,7 +138,7 @@
fake_j.push_back(&j);
// Where was the joint when the optical switch triggered?
- if (original_switch_state_ == true)
+ if (switch_state_ == true)
fake_a[0]->state_.position_ = actuator_->state_.last_calibration_rising_edge_;
else
fake_a[0]->state_.position_ = actuator_->state_.last_calibration_falling_edge_;
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-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2008-10-20 19:51:45 UTC (rev 5560)
@@ -175,8 +175,8 @@
uint16_t num_encoder_errors_;
uint8_t encoder_status_;
uint8_t calibration_reading_;
+ int32_t last_calibration_falling_edge_;
int32_t last_calibration_rising_edge_;
- int32_t last_calibration_falling_edge_;
uint16_t board_temperature_;
uint16_t bridge_temperature_;
uint16_t supply_voltage_;
@@ -255,7 +255,7 @@
enum
{
LIMIT_SENSOR_0_STATE = 1, LIMIT_SENSOR_1_STATE = 2,
- LIMIT_ON_TO_OFF = 4, LIMIT_OFF_TO_ON = 8
+ LIMIT_OFF_TO_ON = 4, LIMIT_ON_TO_OFF = 8
};
// Board configuration parameters
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-20 19:51:45 UTC (rev 5560)
@@ -341,6 +341,8 @@
/ (this_status->timestamp_ - prev_status->timestamp_) * 1e+6;
state.velocity_ = state.encoder_velocity_ / actuator_info_.pulses_per_revolution_ * 2 * M_PI;
state.calibration_reading_ = this_status->calibration_reading_ & LIMIT_SENSOR_0_STATE;
+ state.calibration_rising_edge_valid_ = this_status->calibration_reading_ & LIMIT_OFF_TO_ON;
+ state.calibration_falling_edge_valid_ = this_status->calibration_reading_ & LIMIT_ON_TO_OFF;
state.last_calibration_rising_edge_ = double(this_status->last_calibration_rising_edge_) / actuator_info_.pulses_per_revolution_ * 2 * M_PI;
state.last_calibration_falling_edge_ = double(this_status->last_calibration_falling_edge_) / actuator_info_.pulses_per_revolution_ * 2 * M_PI;
state.is_enabled_ = this_status->mode_ != MODE_OFF;
Modified: pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h
===================================================================
--- pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h 2008-10-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h 2008-10-20 19:51:45 UTC (rev 5560)
@@ -42,6 +42,14 @@
class ActuatorState{
public:
ActuatorState() :
+ timestamp_(0),
+ encoder_count_(0),
+ position_(0),
+ encoder_velocity_(0),
+ velocity_(0),
+ calibration_reading_(0),
+ calibration_rising_edge_valid_(0),
+ calibration_falling_edge_valid_(0),
last_calibration_rising_edge_(0),
last_calibration_falling_edge_(0),
is_enabled_(0),
@@ -52,6 +60,7 @@
last_requested_effort_(0),
last_commanded_effort_(0),
last_measured_effort_(0),
+ motor_voltage_(0),
num_encoder_errors_(0),
zero_offset_(0)
{}
@@ -63,6 +72,8 @@
double velocity_;
bool calibration_reading_;
+ bool calibration_rising_edge_valid_;
+ bool calibration_falling_edge_valid_;
double last_calibration_rising_edge_;
double last_calibration_falling_edge_;
Modified: pkg/trunk/mechanism/mechanism_control/scripts/listen.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-10-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-10-20 19:51:45 UTC (rev 5560)
@@ -33,8 +33,10 @@
print " encoder_velocity: %.4f" % a.encoder_velocity
print " velocity: %.4f" % a.velocity
print " calibration_reading: %d" % a.calibration_reading
- print " last_calibration_rising_edge: %d" % a.last_calibration_rising_edge
- print " last_calibration_falling_edge: %d" % a.last_calibration_falling_edge
+ print " calibration_rising_edge_valid: %d" % a.calibration_rising_edge_valid
+ print " calibration_falling_edge_valid: %d" % a.calibration_falling_edge_valid
+ print " last_calibration_rising_edge: %.4f" % a.last_calibration_rising_edge
+ print " last_calibration_falling_edge: %.4f" % a.last_calibration_falling_edge
print " is_enabled: %d" % a.is_enabled
print " run_stop_hit: %d" % a.run_stop_hit
print " last_requested_current: %.4f" % a.last_requested_current
Modified: pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-10-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-10-20 19:51:45 UTC (rev 5560)
@@ -261,6 +261,8 @@
out->encoder_velocity = in->encoder_velocity_;
out->velocity = in->velocity_;
out->calibration_reading = in->calibration_reading_;
+ out->calibration_rising_edge_valid = in->calibration_rising_edge_valid_;
+ out->calibration_falling_edge_valid = in->calibration_falling_edge_valid_;
out->last_calibration_rising_edge = in->last_calibration_rising_edge_;
out->last_calibration_falling_edge = in->last_calibration_falling_edge_;
out->is_enabled = in->is_enabled_;
Modified: pkg/trunk/robot_msgs/msg/ActuatorState.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/ActuatorState.msg 2008-10-20 19:38:01 UTC (rev 5559)
+++ pkg/trunk/robot_msgs/msg/ActuatorState.msg 2008-10-20 19:51:45 UTC (rev 5560)
@@ -5,6 +5,8 @@
float64 encoder_velocity
float64 velocity
byte calibration_reading
+byte calibration_rising_edge_valid
+byte calibration_falling_edge_valid
float64 last_calibration_rising_edge
float64 last_calibration_falling_edge
byte is_enabled
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|