|
From: <rob...@us...> - 2008-10-04 00:34:01
|
Revision: 5047
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5047&view=rev
Author: rob_wheeler
Date: 2008-10-04 00:33:58 +0000 (Sat, 04 Oct 2008)
Log Message:
-----------
Return calibration data in radians.
Set WG0X safety disable when command enabled
Modified Paths:
--------------
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h
pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg
pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp
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-04 00:26:17 UTC (rev 5046)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2008-10-04 00:33:58 UTC (rev 5047)
@@ -237,7 +237,7 @@
enum
{
MODE_OFF = 0x00, MODE_CURRENT = 0x01, MODE_ENABLE = 0x02,
- MODE_UNDERVOLTAGE = 0x04, MODE_RESET = 0x80
+ MODE_UNDERVOLTAGE = 0x04, MODE_SAFETY_RESET = 0x10, MODE_RESET = 0x80
};
enum
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-04 00:26:17 UTC (rev 5046)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-10-04 00:33:58 UTC (rev 5047)
@@ -222,6 +222,7 @@
node->log(ros::FATAL, "Unable to load configuration information");
return -1;
}
+ printf("Device #%02d: Serial #: %05d\n", sh_->get_ring_position(), config_info_.device_serial_number_);
if (readEeprom(sh_) < 0)
{
@@ -303,7 +304,7 @@
memset(c, 0, sizeof(WG0XCommand));
c->programmed_current_ = int(command.current_ / config_info_.nominal_current_scale_);
- c->mode_ = command.enable_ ? (MODE_ENABLE | MODE_CURRENT) : MODE_OFF;
+ c->mode_ = command.enable_ ? (MODE_ENABLE | MODE_CURRENT | MODE_SAFETY_RESET) : MODE_OFF;
c->checksum_ = rotateRight8(computeChecksum(c, sizeof(WG0XCommand) - 1));
}
@@ -353,8 +354,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_;
- state.last_calibration_low_transition_ = double(this_status->last_calibration_low_transition_) / actuator_info_.pulses_per_revolution_;
+ 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.is_enabled_ = this_status->mode_ != MODE_OFF;
state.run_stop_hit_ = (this_status->mode_ & MODE_UNDERVOLTAGE) != 0;
Modified: pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg
===================================================================
--- pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg 2008-10-04 00:26:17 UTC (rev 5046)
+++ pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg 2008-10-04 00:33:58 UTC (rev 5047)
@@ -5,8 +5,8 @@
float64 encoder_velocity
float64 velocity
byte calibration_reading
-int32 last_calibration_high_transition
-int32 last_calibration_low_transition
+float64 last_calibration_high_transition
+float64 last_calibration_low_transition
byte is_enabled
byte run_stop_hit
float64 last_requested_current
Modified: pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp 2008-10-04 00:26:17 UTC (rev 5046)
+++ pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp 2008-10-04 00:33:58 UTC (rev 5047)
@@ -58,11 +58,13 @@
TiXmlElement *ael = elt->FirstChildElement("actuator");
const char *actuator_name = ael ? ael->Attribute("name") : NULL;
- if (!actuator_name || robot->getActuatorIndex(actuator_name) < 0)
+ Actuator *a;
+ if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
{
fprintf(stderr, "SimpleTransmission could not find actuator named \"%s\"\n", actuator_name);
return false;
}
+ a->command_.enable_ = true;
actuator_names_.push_back(actuator_name);
mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
@@ -95,7 +97,6 @@
assert(as.size() == 1);
assert(js.size() == 1);
as[0]->command_.effort_ = js[0]->commanded_effort_ / mechanical_reduction_;
- as[0]->command_.enable_ = true;
}
void SimpleTransmission::propagateEffortBackwards(
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|