|
From: <rob...@us...> - 2008-10-15 23:54:38
|
Revision: 5415
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5415&view=rev
Author: rob_wheeler
Date: 2008-10-15 23:54:32 +0000 (Wed, 15 Oct 2008)
Log Message:
-----------
last_calibration_high_transition -> last_calibration_rising_edge
last_calibration_low_transition -> last_calibration_falling_edge
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/CMakeLists.txt
pkg/trunk/mechanism/mechanism_control/scripts/listen.py
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/robot_msgs/msg/ActuatorState.msg
Removed Paths:
-------------
pkg/trunk/mechanism/mechanism_control/msg/
pkg/trunk/mechanism/mechanism_control/srv/
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-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2008-10-15 23:54:32 UTC (rev 5415)
@@ -127,9 +127,9 @@
// Where was the joint when the optical switch triggered?
if (original_switch_state_ == true)
- fake_a[0]->state_.position_ = actuator_->state_.last_calibration_high_transition_;
+ fake_a[0]->state_.position_ = actuator_->state_.last_calibration_rising_edge_;
else
- fake_a[0]->state_.position_ = actuator_->state_.last_calibration_low_transition_;
+ fake_a[0]->state_.position_ = actuator_->state_.last_calibration_falling_edge_;
transmission_->propagatePosition(fake_a, fake_j);
// What is the actuator position at the joint's zero?
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-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp 2008-10-15 23:54:32 UTC (rev 5415)
@@ -139,9 +139,9 @@
// Where was the joint when the optical switch triggered?
if (original_switch_state_ == true)
- fake_a[0]->state_.position_ = actuator_->state_.last_calibration_high_transition_;
+ fake_a[0]->state_.position_ = actuator_->state_.last_calibration_rising_edge_;
else
- fake_a[0]->state_.position_ = actuator_->state_.last_calibration_low_transition_;
+ fake_a[0]->state_.position_ = actuator_->state_.last_calibration_falling_edge_;
transmission_->propagatePosition(fake_a, fake_j);
// What is the actuator position at the joint's zero?
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-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2008-10-15 23:54:32 UTC (rev 5415)
@@ -175,8 +175,8 @@
uint16_t num_encoder_errors_;
uint8_t encoder_status_;
uint8_t calibration_reading_;
- int32_t last_calibration_high_transition_;
- int32_t last_calibration_low_transition_;
+ int32_t last_calibration_rising_edge_;
+ int32_t last_calibration_falling_edge_;
uint16_t board_temperature_;
uint16_t bridge_temperature_;
uint16_t supply_voltage_;
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-15 23:54:32 UTC (rev 5415)
@@ -341,8 +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.last_calibration_high_transition_ = double(this_status->last_calibration_high_transition_) / actuator_info_.pulses_per_revolution_ * 2 * M_PI;
- state.last_calibration_low_transition_ = double(this_status->last_calibration_low_transition_) / actuator_info_.pulses_per_revolution_ * 2 * M_PI;
+ 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;
state.run_stop_hit_ = (this_status->mode_ & MODE_UNDERVOLTAGE) != 0;
@@ -806,8 +806,8 @@
ADD_STRING_FMT("Num encoder_errors", "%d", status->num_encoder_errors_);
ADD_STRING_FMT("Encoder status", "%d", status->encoder_status_);
ADD_STRING_FMT("Calibration reading", "%d", status->calibration_reading_);
- ADD_STRING_FMT("Last calibration high transition", "%d", status->last_calibration_high_transition_);
- ADD_STRING_FMT("Last calibration low transition", "%d", status->last_calibration_low_transition_);
+ ADD_STRING_FMT("Last calibration rising edge", "%d", status->last_calibration_rising_edge_);
+ ADD_STRING_FMT("Last calibration falling edge", "%d", status->last_calibration_falling_edge_);
ADD_STRING_FMT("Board temperature", "%f", 0.0078125 * status->board_temperature_);
ADD_STRING_FMT("Bridge temperature", "%f", 0.0078125 * status->bridge_temperature_);
ADD_STRING_FMT("Supply voltage", "%f", status->supply_voltage_ * config_info_.nominal_voltage_scale_);
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-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h 2008-10-15 23:54:32 UTC (rev 5415)
@@ -42,8 +42,8 @@
class ActuatorState{
public:
ActuatorState() :
- last_calibration_high_transition_(0),
- last_calibration_low_transition_(0),
+ last_calibration_rising_edge_(0),
+ last_calibration_falling_edge_(0),
is_enabled_(0),
run_stop_hit_(0),
last_requested_current_(0),
@@ -63,8 +63,8 @@
double velocity_;
bool calibration_reading_;
- double last_calibration_high_transition_; // Last transition from high to low.
- double last_calibration_low_transition_;
+ double last_calibration_rising_edge_;
+ double last_calibration_falling_edge_;
bool is_enabled_;
bool run_stop_hit_;
Modified: pkg/trunk/mechanism/mechanism_control/CMakeLists.txt
===================================================================
--- pkg/trunk/mechanism/mechanism_control/CMakeLists.txt 2008-10-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/mechanism/mechanism_control/CMakeLists.txt 2008-10-15 23:54:32 UTC (rev 5415)
@@ -1,8 +1,6 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
rospack(mechanism_control)
-genmsg()
-gensrv()
rospack_add_library(mechanism_control src/mechanism_control.cpp)
#rospack_add_executable(ms_publisher_test test/ms_publisher_test.cpp)
#rospack_add_rostest(test/test-mechanism-state-cpp.xml)
Modified: pkg/trunk/mechanism/mechanism_control/scripts/listen.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-10-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-10-15 23:54:32 UTC (rev 5415)
@@ -33,8 +33,8 @@
print " encoder_velocity: %.4f" % a.encoder_velocity
print " velocity: %.4f" % a.velocity
print " calibration_reading: %d" % a.calibration_reading
- print " last_calibration_high_transition: %d" % a.last_calibration_high_transition
- print " last_calibration_low_transition: %d" % a.last_calibration_low_transition
+ print " last_calibration_rising_edge: %d" % a.last_calibration_rising_edge
+ print " last_calibration_falling_edge: %d" % 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-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-10-15 23:54:32 UTC (rev 5415)
@@ -266,8 +266,8 @@
out->encoder_velocity = in->encoder_velocity_;
out->velocity = in->velocity_;
out->calibration_reading = in->calibration_reading_;
- out->last_calibration_high_transition = in->last_calibration_high_transition_;
- out->last_calibration_low_transition = in->last_calibration_low_transition_;
+ 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_;
out->run_stop_hit = in->run_stop_hit_;
out->last_requested_current = in->last_requested_current_;
Modified: pkg/trunk/robot_msgs/msg/ActuatorState.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/ActuatorState.msg 2008-10-15 23:50:11 UTC (rev 5414)
+++ pkg/trunk/robot_msgs/msg/ActuatorState.msg 2008-10-15 23:54:32 UTC (rev 5415)
@@ -5,8 +5,8 @@
float64 encoder_velocity
float64 velocity
byte calibration_reading
-float64 last_calibration_high_transition
-float64 last_calibration_low_transition
+float64 last_calibration_rising_edge
+float64 last_calibration_falling_edge
byte is_enabled
byte run_stop_hit
float64 last_requested_current
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|