File tree Expand file tree Collapse file tree 1 file changed +2
-2
lines changed Expand file tree Collapse file tree 1 file changed +2
-2
lines changed Original file line number Diff line number Diff line change @@ -416,7 +416,7 @@ bool GPIOController::setAnalogOutput(ur_msgs::srv::SetAnalogOutput::Request::Sha
416416
417417 std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value (ASYNC_WAITING);
418418 std::ignore = command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->data .pin ].set_value (
419- static_cast <float >(req->data .state ));
419+ static_cast <double >(req->data .state ));
420420 std::ignore =
421421 command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_DOMAIN].set_value (static_cast <double >(req->data .domain ));
422422
@@ -518,7 +518,7 @@ bool GPIOController::setPayload(const ur_msgs::srv::SetPayload::Request::SharedP
518518 // reset success flag
519519 std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_ASYNC_SUCCESS].set_value (ASYNC_WAITING);
520520
521- std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_MASS].set_value (req->mass );
521+ std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_MASS].set_value (static_cast < double >( req->mass ) );
522522 std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_X].set_value (req->center_of_gravity .x );
523523 std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_Y].set_value (req->center_of_gravity .y );
524524 std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_Z].set_value (req->center_of_gravity .z );
You can’t perform that action at this time.
0 commit comments